diff --git a/src/.vscode/settings.json b/src/.vscode/settings.json new file mode 100644 index 0000000..0db5873 --- /dev/null +++ b/src/.vscode/settings.json @@ -0,0 +1,3 @@ +{ + "cmake.configureOnOpen": true +} \ No newline at end of file diff --git a/src/ZLAC8015D_python/.gitignore b/src/ZLAC8015D_python/.gitignore deleted file mode 100644 index b08ba21..0000000 --- a/src/ZLAC8015D_python/.gitignore +++ /dev/null @@ -1,5 +0,0 @@ -build/ -dist/ -zlac8015d.egg-info/ -__pycache__/ - diff --git a/src/ZLAC8015D_python/examples/__pycache__/ZLAC8015D.cpython-38.pyc b/src/ZLAC8015D_python/examples/__pycache__/ZLAC8015D.cpython-38.pyc new file mode 100644 index 0000000..3fb1cf2 --- /dev/null +++ b/src/ZLAC8015D_python/examples/__pycache__/ZLAC8015D.cpython-38.pyc Binary files differ diff --git a/src/ZLAC8015D_python/zlac8015d/__init__.py b/src/ZLAC8015D_python/zlac8015d/__init__.py deleted file mode 100644 index 47534ee..0000000 --- a/src/ZLAC8015D_python/zlac8015d/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from zlac8015d import ZLAC8015D \ No newline at end of file diff --git a/src/emcl2/CMakeLists.txt b/src/emcl2/CMakeLists.txt new file mode 100644 index 0000000..5f2d64f --- /dev/null +++ b/src/emcl2/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.0.2) +project(emcl2) + +set(CMAKE_CXX_FLAGS "-std=c++17 -O3 ${CMAKE_CXX_FLAGS}") + +find_package(catkin REQUIRED COMPONENTS + roscpp + geometry_msgs + tf2 + tf2_ros +) + +catkin_package( +) + +include_directories(include ${catkin_INCLUDE_DIRS} ) + +add_library(Mcl_emcl2 src/Mcl.cpp) +#add_library(ExpResetMcl_emcl2 src/ExpResetMcl.cpp) +add_library(ExpResetMcl2_emcl2 src/ExpResetMcl2.cpp) +add_library(Particle_emcl2 src/Particle.cpp) +add_library(OdomModel_emcl2 src/OdomModel.cpp) +add_library(Pose_emcl2 src/Pose.cpp) +add_library(Scan_emcl2 src/Scan.cpp) +add_library(LikelihoodFieldMap_emcl2 src/LikelihoodFieldMap.cpp) + +add_executable(emcl2_node src/emcl2_node.cpp) + +add_dependencies(emcl2_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +target_link_libraries(emcl2_node Mcl_emcl2 ExpResetMcl2_emcl2 Particle_emcl2 Pose_emcl2 Scan_emcl2 OdomModel_emcl2 LikelihoodFieldMap_emcl2 ${catkin_LIBRARIES}) diff --git a/src/emcl2/COPYING b/src/emcl2/COPYING new file mode 100644 index 0000000..0a04128 --- /dev/null +++ b/src/emcl2/COPYING @@ -0,0 +1,165 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + + This version of the GNU Lesser General Public License incorporates +the terms and conditions of version 3 of the GNU General Public +License, supplemented by the additional permissions listed below. + + 0. Additional Definitions. + + As used herein, "this License" refers to version 3 of the GNU Lesser +General Public License, and the "GNU GPL" refers to version 3 of the GNU +General Public License. + + "The Library" refers to a covered work governed by this License, +other than an Application or a Combined Work as defined below. + + An "Application" is any work that makes use of an interface provided +by the Library, but which is not otherwise based on the Library. +Defining a subclass of a class defined by the Library is deemed a mode +of using an interface provided by the Library. + + A "Combined Work" is a work produced by combining or linking an +Application with the Library. The particular version of the Library +with which the Combined Work was made is also called the "Linked +Version". + + The "Minimal Corresponding Source" for a Combined Work means the +Corresponding Source for the Combined Work, excluding any source code +for portions of the Combined Work that, considered in isolation, are +based on the Application, and not on the Linked Version. + + The "Corresponding Application Code" for a Combined Work means the +object code and/or source code for the Application, including any data +and utility programs needed for reproducing the Combined Work from the +Application, but excluding the System Libraries of the Combined Work. + + 1. Exception to Section 3 of the GNU GPL. + + You may convey a covered work under sections 3 and 4 of this License +without being bound by section 3 of the GNU GPL. + + 2. Conveying Modified Versions. + + If you modify a copy of the Library, and, in your modifications, a +facility refers to a function or data to be supplied by an Application +that uses the facility (other than as an argument passed when the +facility is invoked), then you may convey a copy of the modified +version: + + a) under this License, provided that you make a good faith effort to + ensure that, in the event an Application does not supply the + function or data, the facility still operates, and performs + whatever part of its purpose remains meaningful, or + + b) under the GNU GPL, with none of the additional permissions of + this License applicable to that copy. + + 3. Object Code Incorporating Material from Library Header Files. + + The object code form of an Application may incorporate material from +a header file that is part of the Library. You may convey such object +code under terms of your choice, provided that, if the incorporated +material is not limited to numerical parameters, data structure +layouts and accessors, or small macros, inline functions and templates +(ten or fewer lines in length), you do both of the following: + + a) Give prominent notice with each copy of the object code that the + Library is used in it and that the Library and its use are + covered by this License. + + b) Accompany the object code with a copy of the GNU GPL and this license + document. + + 4. Combined Works. + + You may convey a Combined Work under terms of your choice that, +taken together, effectively do not restrict modification of the +portions of the Library contained in the Combined Work and reverse +engineering for debugging such modifications, if you also do each of +the following: + + a) Give prominent notice with each copy of the Combined Work that + the Library is used in it and that the Library and its use are + covered by this License. + + b) Accompany the Combined Work with a copy of the GNU GPL and this license + document. + + c) For a Combined Work that displays copyright notices during + execution, include the copyright notice for the Library among + these notices, as well as a reference directing the user to the + copies of the GNU GPL and this license document. + + d) Do one of the following: + + 0) Convey the Minimal Corresponding Source under the terms of this + License, and the Corresponding Application Code in a form + suitable for, and under terms that permit, the user to + recombine or relink the Application with a modified version of + the Linked Version to produce a modified Combined Work, in the + manner specified by section 6 of the GNU GPL for conveying + Corresponding Source. + + 1) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (a) uses at run time + a copy of the Library already present on the user's computer + system, and (b) will operate properly with a modified version + of the Library that is interface-compatible with the Linked + Version. + + e) Provide Installation Information, but only if you would otherwise + be required to provide such information under section 6 of the + GNU GPL, and only to the extent that such information is + necessary to install and execute a modified version of the + Combined Work produced by recombining or relinking the + Application with a modified version of the Linked Version. (If + you use option 4d0, the Installation Information must accompany + the Minimal Corresponding Source and Corresponding Application + Code. If you use option 4d1, you must provide the Installation + Information in the manner specified by section 6 of the GNU GPL + for conveying Corresponding Source.) + + 5. Combined Libraries. + + You may place library facilities that are a work based on the +Library side by side in a single library together with other library +facilities that are not Applications and are not covered by this +License, and convey such a combined library under terms of your +choice, if you do both of the following: + + a) Accompany the combined library with a copy of the same work based + on the Library, uncombined with any other library facilities, + conveyed under the terms of this License. + + b) Give prominent notice with the combined library that part of it + is a work based on the Library, and explaining where to find the + accompanying uncombined form of the same work. + + 6. Revised Versions of the GNU Lesser General Public License. + + The Free Software Foundation may publish revised and/or new versions +of the GNU Lesser General Public License from time to time. Such new +versions will be similar in spirit to the present version, but may +differ in detail to address new problems or concerns. + + Each version is given a distinguishing version number. If the +Library as you received it specifies that a certain numbered version +of the GNU Lesser General Public License "or any later version" +applies to it, you have the option of following the terms and +conditions either of that published version or of any later version +published by the Free Software Foundation. If the Library as you +received it does not specify a version number of the GNU Lesser +General Public License, you may choose any version of the GNU Lesser +General Public License ever published by the Free Software Foundation. + + If the Library as you received it specifies that a proxy can decide +whether future versions of the GNU Lesser General Public License shall +apply, that proxy's public statement of acceptance of any version is +permanent authorization for you to choose that version for the +Library. diff --git a/src/emcl2/README.md b/src/emcl2/README.md new file mode 100644 index 0000000..7e1ce04 --- /dev/null +++ b/src/emcl2/README.md @@ -0,0 +1,125 @@ +# emcl2: mcl with expansion resetting (version 2) + +![test](https://github.com/ryuichiueda/emcl2/actions/workflows/test.yml/badge.svg) + +emcl is an alternative Monte Carlo localization (MCL) package to amcl (http://wiki.ros.org/amcl). Differently from amcl, KLD-sampling and adaptive MCL are not implemented. Instead, the expansion resetting and other features are implemented[^1][^2]. + +This package is an improved version of [ryuichi/emcl](https://github.com/ryuichiueda/emcl). This version works well in crowded or outdoor environments. + +## demo movies + +[![](https://img.youtube.com/vi/dqS7KgGxwBs/0.jpg)](https://www.youtube.com/watch?v=dqS7KgGxwBs) + +[![](https://img.youtube.com/vi/n9tzKY6ua_o/0.jpg)](https://www.youtube.com/watch?v=n9tzKY6ua_o) + +## Nodes + +### emcl2_node + +This node calculates the alpha value with a different algorithm than `emcl_node` in [ryuichi/emcl](https://github.com/ryuichiueda/emcl). This node counts the particles that make lasers penetrate occupancy cells. Specifically, this node chooses some particles at a rate of `~extraction_rate` and checks each of them with the following procedure: + +* maps a set of laser scan on the occupancy grid map based on the pose of the particle +* judges the pose of the particle as wrong if all of lasers in a `~range_threshold`[rad] range penatrate occupancy grids + +If the rate of the wrong particles is greater than `~alpha_threshold`, the node invokes a reset. + +This node also has a sensor resetting algorithm. When `~sensor_reset` is true, a particle with laser penetration is dragged back from occupied cells. + +#### Subscribed Topics + +* scan ([sensor_msgs/LaserScan](http://docs.ros.org/en/api/sensor_msgs/html/msg/LaserScan.html)) + * laser scans +* tf ([tf/tfMessage](http://docs.ros.org/en/api/tf/html/msg/tfMessage.html)) + * transforms +* initialpose ([geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/en/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)) + * pose of particles for replacement + +#### Published Topics + +* mcl_pose ([geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/en/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)) + * the mean pose of the particles with covariance +* particlecloud ([geometry_msgs/PoseArray](http://docs.ros.org/en/api/geometry_msgs/html/msg/PoseArray.html)) + * poses of the particles +* tf ([tf/tfMessage](http://docs.ros.org/en/api/tf/html/msg/tfMessage.html)) + * the transform from odom (which can be remapped via the ~odom_frame_id parameter) to map +* alpha (std_msgs/Float32) + * marginal likelihood of particles after sensor update + +#### Services + +* global_localization ([std_srvs/Empty](http://docs.ros.org/en/api/std_srvs/html/srv/Empty.html)) + * Initiate global localization, wherein all particles are dispersed randomly through the free space in the map. + +#### Services Called + +* static_map ([nav_msgs/GetMap](http://docs.ros.org/en/api/nav_msgs/html/srv/GetMap.html)) + * Initiate the map for localization. + +#### parameters + +* ~odom_freq (int, default: 20 [Hz]) + * frequency of odometry update +* ~num_particles (int, default: 1000) + * number of particles +* ~odom_frame_id (string, default: "odom") + * the frame for odometry +* ~footprint_frame_id (string, default: "base_footprint") + * the frame of the localized robot's base +* ~base_frame_id (string, default: "base_link") + * the frame of the robot's base. It is used for calculating the position and orientation of the LiDAR. +* ~global_frame_id (string, default: "map") + * the frame for localization +* ~initial_pose_x (double, default: 0.0 [m]) + * initial x coordinate of particles +* ~initial_pose_y (double, default: 0.0 [m]) + * initial y coordinate of particles +* ~initial_pose_a (double, default: 0.0 [rad]) + * initial yaw coordinate of particles +* ~odom_fw_dev_per_fw (double, default: 0.19 [m/m]) + * standard deviation of forward motion noise by forward motion +* ~odom_fw_dev_per_rot (double, default: 0.0001 [m/rad]) + * standard deviation of forward motion noise by rotational motion +* ~odom_rot_dev_per_fw (double, default: 0.13 [rad/m]) + * standard deviation of rotational motion noise by forward motion +* ~odom_rot_dev_per_rot (double, default: 0.2 [rad/rad]) + * standard deviation of rotational motion noise by rotational motion +* ~laser_likelihood_max_dist (double, default: 0.2 meters) + * maximum distance to inflate occupied cells on the likelihood field map +* ~scan_increment (int, default: 1) + * increment number when beams are picked from their sequence; the larger this number is, the fewer number of beams are used for calculation of likelihood +* ~alpha_threshold (double, default: 0.5) + * threshold of the alpha value for expansion resetting +* ~expansion_radius_position (double, default: 0.1[m]) + * maximum change of the position on the xy-plane when the reset replaces a particle +* ~expansion_radius_orientation (double, default: 0.2[rad]) + * maximum change of the yaw angle when the reset replaces a particle +* ~extraction_rate (double, default: 0.1) + * rate of particles that are checked by the node +* ~range_threshold (double, default: 0.1[rad]) + * threshold of the range of lasers; if all lasers on this range penetrate occupancy cells, the pose of the particle is judged as wrong +* ~sensor_reset (bool, default: true) + * flag for sensor resettings + + +The followings have never been implemented yet. + +* ~laser_min_range (double, default: 0.0[m]) + * threshold for discarding scans whose ranges are smaller than this value +* ~laser_max_range (double, default: 100000000.0[m]) + * threshold for discarding scans whose ranges are larger than this value + + + + +## ROS version + +* ROS Noetic Ninjemys (on Ubuntu 20.04 LTS, test on my note PC) +* ROS Melodic Morenia (on Ubuntu 18.04 LTS, test on GitHub Actions) + + +## citation + +[^1]: R. Ueda: "[Syokai Kakuritsu Robotics (lecture note on probabilistic robotics)](https://www.amazon.co.jp/dp/B082SN3VTD)," Kodansya, 2019. + +[^2]: R. Ueda, T. Arai, K. Sakamoto, T. Kikuchi, S. Kamiya: Expansion resetting for recovery from fatal error in Monte Carlo localization - comparison with sensor resetting methods, IEEE/RSJ IROS, pp.2481-2486, 2004. + diff --git a/src/emcl2/include/emcl/ExpResetMcl.h b/src/emcl2/include/emcl/ExpResetMcl.h new file mode 100644 index 0000000..b5aa5b6 --- /dev/null +++ b/src/emcl2/include/emcl/ExpResetMcl.h @@ -0,0 +1,33 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef EXP_PF_H__ +#define EXP_PF_H__ + +#include "emcl/Mcl.h" + +namespace emcl2 { + +class ExpResetMcl : public Mcl +{ +public: + ExpResetMcl(const Pose &p, int num, const Scan &scan, + const std::shared_ptr &odom_model, + const std::shared_ptr &map, + double alpha_th, double open_space_th, + double expansion_radius_position, double expansion_radius_orientation); + ~ExpResetMcl(); + + void sensorUpdate(double lidar_x, double lidar_y, double lidar_t, bool inv); +private: + double alpha_threshold_; + double open_space_threshold_; + double expansion_radius_position_; + double expansion_radius_orientation_; + + void expansionReset(void); +}; + +} + +#endif diff --git a/src/emcl2/include/emcl/ExpResetMcl2.h b/src/emcl2/include/emcl/ExpResetMcl2.h new file mode 100644 index 0000000..83d62f2 --- /dev/null +++ b/src/emcl2/include/emcl/ExpResetMcl2.h @@ -0,0 +1,41 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef EXP_PF2_H__ +#define EXP_PF2_H__ + +#include "emcl/Mcl.h" + +namespace emcl2 { + +class ExpResetMcl2 : public Mcl +{ +public: + ExpResetMcl2(const Pose &p, int num, const Scan &scan, + const std::shared_ptr &odom_model, + const std::shared_ptr &map, + double alpha_th, + double expansion_radius_position, double expansion_radius_orientation, + double extraction_rate, double successive_penetration_threshold, + bool sensor_reset); + ~ExpResetMcl2(); + + void sensorUpdate(double lidar_x, double lidar_y, double lidar_t, bool inv); +private: + double alpha_threshold_; + double expansion_radius_position_; + double expansion_radius_orientation_; + + double extraction_rate_; + double range_threshold_; + bool sensor_reset_; + + void expansionReset(void); + +//bool Particle::isPenetrating( + double nonPenetrationRate(int skip, LikelihoodFieldMap *map, Scan &scan); +}; + +} + +#endif diff --git a/src/emcl2/include/emcl/LikelihoodFieldMap.h b/src/emcl2/include/emcl/LikelihoodFieldMap.h new file mode 100644 index 0000000..b30bf0d --- /dev/null +++ b/src/emcl2/include/emcl/LikelihoodFieldMap.h @@ -0,0 +1,42 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef OCC_GRID_MAP_H__ +#define OCC_GRID_MAP_H__ + +#include +#include +#include "emcl/Scan.h" +#include "emcl/Pose.h" +#include "nav_msgs/OccupancyGrid.h" + +namespace emcl2 { + +class LikelihoodFieldMap +{ +public: + LikelihoodFieldMap(const nav_msgs::OccupancyGrid &map, double likelihood_range); + ~LikelihoodFieldMap(); + + void setLikelihood(int x, int y, double range); + double likelihood(double x, double y); + + std::vector likelihoods_; + int width_; + int height_; + + double resolution_; + double origin_x_; + double origin_y_; + + void drawFreePoses(int num, std::vector &result); +private: + std::vector > free_cells_; + + void normalize(void); +}; + +} + +#endif + diff --git a/src/emcl2/include/emcl/Mcl.h b/src/emcl2/include/emcl/Mcl.h new file mode 100644 index 0000000..d0f6a95 --- /dev/null +++ b/src/emcl2/include/emcl/Mcl.h @@ -0,0 +1,67 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef PF_H__ +#define PF_H__ + +#include +#include +#include + +#include "emcl/Particle.h" +#include "emcl/OdomModel.h" +#include "emcl/LikelihoodFieldMap.h" + +#include "nav_msgs/OccupancyGrid.h" +#include "sensor_msgs/LaserScan.h" + +namespace emcl2 { + +class Mcl +{ +public: + Mcl(){} + Mcl(const Pose &p, int num, const Scan &scan, + const std::shared_ptr &odom_model, + const std::shared_ptr &map); + ~Mcl(); + + std::vector particles_; + double alpha_; + + void sensorUpdate(double lidar_x, double lidar_y, double lidar_t, bool inv); + void motionUpdate(double x, double y, double t); + + void initialize(double x, double y, double t); + + void setScan(const sensor_msgs::LaserScan::ConstPtr &msg); + void meanPose(double &x_mean, double &y_mean, double &t_mean, + double &x_var, double &y_var, double &t_var, + double &xy_cov, double &yt_cov, double &tx_cov); + + void simpleReset(void); + + static double cos_[(1<<16)]; + static double sin_[(1<<16)]; +protected: + Pose *last_odom_; + Pose *prev_odom_; + + Scan scan_; + int processed_seq_; + + double normalizeAngle(double t); + void resampling(void); + double normalizeBelief(void); + void resetWeight(void); + + std::shared_ptr odom_model_; + std::shared_ptr map_; +}; + +double Mcl::cos_[(1<<16)]; +double Mcl::sin_[(1<<16)]; + +} + +#endif diff --git a/src/emcl2/include/emcl/OdomModel.h b/src/emcl2/include/emcl/OdomModel.h new file mode 100644 index 0000000..e755809 --- /dev/null +++ b/src/emcl2/include/emcl/OdomModel.h @@ -0,0 +1,37 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef ODOM_MODEL_H__ +#define ODOM_MODEL_H__ + +#include + +namespace emcl2 { + + + +class OdomModel +{ +public: + OdomModel(double ff, double fr, double rf, double rr); + void setDev(double length, double angle); + double drawFwNoise(void); + double drawRotNoise(void); +private: + double fw_dev_; + double rot_dev_; + + double fw_var_per_fw_; + double fw_var_per_rot_; + double rot_var_per_fw_; + double rot_var_per_rot_; + + std::normal_distribution<> std_norm_dist_; + + std::random_device seed_gen_; + std::default_random_engine engine_; +}; + +} + +#endif diff --git a/src/emcl2/include/emcl/Particle.h b/src/emcl2/include/emcl/Particle.h new file mode 100644 index 0000000..97400ec --- /dev/null +++ b/src/emcl2/include/emcl/Particle.h @@ -0,0 +1,39 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef PARTICLE_H__ +#define PARTICLE_H__ + +#include "emcl/Pose.h" +#include "emcl/LikelihoodFieldMap.h" + +namespace emcl2 { + + + +class Particle +{ +public: + Particle(double x, double y, double t, double w); + + double likelihood(LikelihoodFieldMap *map, Scan &scan); + bool wallConflict(LikelihoodFieldMap *map, Scan &scan, double threshold, bool replace); + Pose p_; + double w_; + + Particle operator =(const Particle &p); +private: + bool isPenetrating(double ox, double oy, double range, uint16_t direction, + LikelihoodFieldMap *map, double &hit_lx, double &hit_ly); + + bool checkWallConflict(LikelihoodFieldMap *map, double ox, double oy, + double range, uint16_t direction, double threshold, bool replace); + + void sensorReset(double ox, double oy, + double range1, uint16_t direction1, double hit_lx1, double hit_ly1, + double range2, uint16_t direction2, double hit_lx2, double hit_ly2); +}; + +} + +#endif diff --git a/src/emcl2/include/emcl/Pose.h b/src/emcl2/include/emcl/Pose.h new file mode 100644 index 0000000..43a5860 --- /dev/null +++ b/src/emcl2/include/emcl/Pose.h @@ -0,0 +1,38 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef POSE_H__ +#define POSE_H__ + +#include + +namespace emcl2 { + +class Pose +{ +public: + Pose(){} + Pose(double x, double y, double t); + + void set(double x, double y, double t); + void set(const Pose &p); + std::string to_s(void); + + void normalizeAngle(void); + void move(double length, double direction, double rotation, + double fw_noise, double rot_noise); + + Pose operator -(const Pose &p) const; + Pose operator =(const Pose &p); + + bool nearlyZero(void); + + double x_, y_, t_; + + uint16_t get16bitRepresentation(void); + static uint16_t get16bitRepresentation(double); +}; + +} + +#endif diff --git a/src/emcl2/include/emcl/Scan.h b/src/emcl2/include/emcl/Scan.h new file mode 100644 index 0000000..5260522 --- /dev/null +++ b/src/emcl2/include/emcl/Scan.h @@ -0,0 +1,37 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef SCAN_H__ +#define SCAN_H__ + +#include +#include + +namespace emcl2 { + +class Scan +{ +public: + int seq_; + int scan_increment_; + double angle_max_; + double angle_min_; + double angle_increment_; + double range_max_; + double range_min_; + + double lidar_pose_x_; + double lidar_pose_y_; + double lidar_pose_yaw_; + + std::vector ranges_; + std::vector directions_16bit_; + + Scan& operator=(const Scan &s); + int countValidBeams(double *rate = NULL); + bool valid(double range); +}; + +} + +#endif diff --git a/src/emcl2/include/emcl/emcl2_node.h b/src/emcl2/include/emcl/emcl2_node.h new file mode 100644 index 0000000..6243dab --- /dev/null +++ b/src/emcl2/include/emcl/emcl2_node.h @@ -0,0 +1,80 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef INTERFACE_EMCL2_H__ +#define INTERFACE_EMCL2_H__ + +#include +#include "emcl/ExpResetMcl2.h" + +#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_listener.h" +#include "tf2_ros/message_filter.h" +#include "tf2/LinearMath/Transform.h" + +#include "sensor_msgs/LaserScan.h" +#include "geometry_msgs/PoseWithCovarianceStamped.h" +#include "std_srvs/Empty.h" + +namespace emcl2 { + +class EMcl2Node +{ +public: + EMcl2Node(); + ~EMcl2Node(); + + void loop(void); + int getOdomFreq(void); +private: + std::shared_ptr pf_; + ros::NodeHandle nh_; + ros::NodeHandle private_nh_; + + ros::Publisher particlecloud_pub_; + ros::Publisher pose_pub_; + ros::Publisher alpha_pub_; + ros::Subscriber laser_scan_sub_; + ros::Subscriber initial_pose_sub_; + + ros::ServiceServer global_loc_srv_; + + std::string footprint_frame_id_; + std::string global_frame_id_; + std::string odom_frame_id_; + std::string scan_frame_id_; + std::string base_frame_id_; + + std::shared_ptr tfb_; + std::shared_ptr tfl_; + std::shared_ptr tf_; + + tf2::Transform latest_tf_; + + int odom_freq_; + bool init_request_; + bool simple_reset_request_; + double init_x_, init_y_, init_t_; + + void publishPose(double x, double y, double t, + double x_dev, double y_dev, double t_dev, + double xy_cov, double yt_cov, double tx_cov); + void publishOdomFrame(double x, double y, double t); + void publishParticles(void); + void sendTf(void); + bool getOdomPose(double& x, double& y, double& yaw); + bool getLidarPose(double& x, double& y, double& yaw, bool& inv); + + void initCommunication(void); + void initPF(void); + std::shared_ptr initMap(void); + std::shared_ptr initOdometry(void); + + void cbScan(const sensor_msgs::LaserScan::ConstPtr &msg); + bool cbSimpleReset(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res); + void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg); +}; + +} + +#endif diff --git a/src/emcl2/launch/emcl2.launch b/src/emcl2/launch/emcl2.launch new file mode 100644 index 0000000..8a20884 --- /dev/null +++ b/src/emcl2/launch/emcl2.launch @@ -0,0 +1,45 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/emcl2/launch/emcl2nav.launch b/src/emcl2/launch/emcl2nav.launch new file mode 100644 index 0000000..64513b5 --- /dev/null +++ b/src/emcl2/launch/emcl2nav.launch @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/emcl2/launch/mcl.launch b/src/emcl2/launch/mcl.launch new file mode 100644 index 0000000..2466f2e --- /dev/null +++ b/src/emcl2/launch/mcl.launch @@ -0,0 +1,37 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/emcl2/launch/mclnav.launch b/src/emcl2/launch/mclnav.launch new file mode 100644 index 0000000..4796312 --- /dev/null +++ b/src/emcl2/launch/mclnav.launch @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/emcl2/package.xml b/src/emcl2/package.xml new file mode 100644 index 0000000..f163001 --- /dev/null +++ b/src/emcl2/package.xml @@ -0,0 +1,25 @@ + + + emcl2 + 0.0.0 + The emcl2 package + + Ryuichi Ueda + LGPL + + https://github.com/ryuichiueda/emcl2/ + + tf2 + tf2_ros + tf2_msgs + tf2_geometry_msgs + + geometry_msgs + nav_msgs + sensor_msgs + + roscpp + + catkin + + diff --git a/src/emcl2/src/ExpResetMcl.cpp b/src/emcl2/src/ExpResetMcl.cpp new file mode 100644 index 0000000..240c0cf --- /dev/null +++ b/src/emcl2/src/ExpResetMcl.cpp @@ -0,0 +1,96 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. + +#include "emcl/ExpResetMcl.h" +#include +#include +#include +#include + +namespace emcl2 { + +ExpResetMcl::ExpResetMcl(const Pose &p, int num, const Scan &scan, + const std::shared_ptr &odom_model, + const std::shared_ptr &map, + double alpha_th, double open_space_th, + double expansion_radius_position, double expansion_radius_orientation) + : alpha_threshold_(alpha_th), open_space_threshold_(open_space_th), + expansion_radius_position_(expansion_radius_position), + expansion_radius_orientation_(expansion_radius_orientation), Mcl::Mcl(p, num, scan, odom_model, map) +{ +} + +ExpResetMcl::~ExpResetMcl() +{ +} + +void ExpResetMcl::sensorUpdate(double lidar_x, double lidar_y, double lidar_t, bool inv) +{ + if(processed_seq_ == scan_.seq_) + return; + + Scan scan; + int seq = -1; + while(seq != scan_.seq_){//trying to copy the latest scan before next + seq = scan_.seq_; + scan = scan_; + } + + scan.lidar_pose_x_ = lidar_x; + scan.lidar_pose_y_ = lidar_y; + scan.lidar_pose_yaw_ = lidar_t; + + int i = 0; + if (!inv) { + for(auto e : scan.ranges_) + scan.directions_16bit_.push_back( + Pose::get16bitRepresentation(scan.angle_min_ + (i++)*scan.angle_increment_) + ); + } else { + for(auto e : scan.ranges_) + scan.directions_16bit_.push_back( + Pose::get16bitRepresentation(scan.angle_max_ - (i++)*scan.angle_increment_) + ); + } + + double valid_pct = 0.0; + int valid_beams = scan.countValidBeams(&valid_pct); + if(valid_beams == 0) + return; + + for(auto &p : particles_) + p.w_ *= p.likelihood(map_.get(), scan); + + alpha_ = normalizeBelief()/valid_beams; + //alpha_ = nonPenetrationRate( particles_.size() / 20, map_.get(), scan); //new version + ROS_INFO("ALPHA: %f / %f", alpha_, alpha_threshold_); + if(alpha_ < alpha_threshold_ and valid_pct > open_space_threshold_){ + ROS_INFO("RESET"); + expansionReset(); + for(auto &p : particles_) + p.w_ *= p.likelihood(map_.get(), scan); + } + + if(normalizeBelief() > 0.000001) + resampling(); + else + resetWeight(); + + processed_seq_ = scan_.seq_; +} + +void ExpResetMcl::expansionReset(void) +{ + for(auto &p : particles_){ + double length = 2*((double)rand()/RAND_MAX - 0.5)*expansion_radius_position_; + double direction = 2*((double)rand()/RAND_MAX - 0.5)*M_PI; + + p.p_.x_ += length*cos(direction); + p.p_.y_ += length*sin(direction); + p.p_.t_ += 2*((double)rand()/RAND_MAX - 0.5)*expansion_radius_orientation_; + p.w_ = 1.0/particles_.size(); + } +} + +} diff --git a/src/emcl2/src/ExpResetMcl2.cpp b/src/emcl2/src/ExpResetMcl2.cpp new file mode 100644 index 0000000..8e83b8a --- /dev/null +++ b/src/emcl2/src/ExpResetMcl2.cpp @@ -0,0 +1,116 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. + +#include "emcl/ExpResetMcl2.h" +#include +#include +#include +#include + +namespace emcl2 { + +ExpResetMcl2::ExpResetMcl2(const Pose &p, int num, const Scan &scan, + const std::shared_ptr &odom_model, + const std::shared_ptr &map, + double alpha_th, + double expansion_radius_position, double expansion_radius_orientation, + double extraction_rate, double range_threshold, bool sensor_reset) + : alpha_threshold_(alpha_th), + expansion_radius_position_(expansion_radius_position), + expansion_radius_orientation_(expansion_radius_orientation), + extraction_rate_(extraction_rate), + range_threshold_(range_threshold), + sensor_reset_(sensor_reset), + Mcl::Mcl(p, num, scan, odom_model, map) +{ +} + +ExpResetMcl2::~ExpResetMcl2() +{ +} + +void ExpResetMcl2::sensorUpdate(double lidar_x, double lidar_y, double lidar_t, bool inv) +{ + if(processed_seq_ == scan_.seq_) + return; + + Scan scan; + int seq = -1; + while(seq != scan_.seq_){//trying to copy the latest scan before next + seq = scan_.seq_; + scan = scan_; + } + + scan.lidar_pose_x_ = lidar_x; + scan.lidar_pose_y_ = lidar_y; + scan.lidar_pose_yaw_ = lidar_t; + + int i = 0; + if(!inv){ + for(auto e : scan.ranges_) + scan.directions_16bit_.push_back( + Pose::get16bitRepresentation(scan.angle_min_ + (i++)*scan.angle_increment_) + ); + }else{ + for(auto e : scan.ranges_) + scan.directions_16bit_.push_back( + Pose::get16bitRepresentation(scan.angle_max_ - (i++)*scan.angle_increment_) + ); + } + + double valid_pct = 0.0; + int valid_beams = scan.countValidBeams(&valid_pct); + if(valid_beams == 0) + return; + + for(auto &p : particles_) + p.w_ *= p.likelihood(map_.get(), scan); + + alpha_ = nonPenetrationRate( (int)(particles_.size()*extraction_rate_), map_.get(), scan); + ROS_INFO("ALPHA: %f / %f", alpha_, alpha_threshold_); + if(alpha_ < alpha_threshold_){ + ROS_INFO("RESET"); + expansionReset(); + for(auto &p : particles_) + p.w_ *= p.likelihood(map_.get(), scan); + } + + if(normalizeBelief() > 0.000001) + resampling(); + else + resetWeight(); + + processed_seq_ = scan_.seq_; +} + +double ExpResetMcl2::nonPenetrationRate(int skip, LikelihoodFieldMap *map, Scan &scan) +{ + static uint16_t shift = 0; + int counter = 0; + int penetrating = 0; + for(int i=shift%skip; i +#include + +namespace emcl2 { + +LikelihoodFieldMap::LikelihoodFieldMap(const nav_msgs::OccupancyGrid &map, double likelihood_range) +{ + width_ = map.info.width; + height_ = map.info.height; + + origin_x_ = map.info.origin.position.x; + origin_y_ = map.info.origin.position.y; + + resolution_ = map.info.resolution; + + for(int x=0; x 50) + setLikelihood(x, y, likelihood_range); + else if(0 <= v and v <= 50) + free_cells_.push_back(std::pair(x,y)); + } + + normalize(); +} + +LikelihoodFieldMap::~LikelihoodFieldMap() +{ + for(auto &e : likelihoods_) + delete [] e; +} + + +double LikelihoodFieldMap::likelihood(double x, double y) +{ + int ix = (int)floor((x - origin_x_)/resolution_); + int iy = (int)floor((y - origin_y_)/resolution_); + + if(ix < 0 or iy < 0 or ix >= width_ or iy >= height_) + return 0.0; + + return likelihoods_[ix][iy]; +} + +void LikelihoodFieldMap::setLikelihood(int x, int y, double range) +{ + int cell_num = (int)ceil(range/resolution_); + std::vector weights; + for(int i=0;i<=cell_num;i++) + weights.push_back(1.0 - (double)i/cell_num); + + for(int i=-cell_num; i<=cell_num; i++) + for(int j=-cell_num; j<=cell_num; j++) + if(i+x >= 0 and j+y >= 0 and i+x < width_ and j+y < height_) + likelihoods_[i+x][j+y] = std::max(likelihoods_[i+x][j+y], + std::min(weights[abs(i)], weights[abs(j)])); +} + +void LikelihoodFieldMap::normalize(void) +{ + double maximum = 0.0; + for(int x=0; x &result) +{ + std::random_device seed_gen; + std::mt19937 engine{seed_gen()}; + std::vector > chosen_cells; + + sample(free_cells_.begin(), free_cells_.end(), back_inserter(chosen_cells), num, engine); + + for(auto &c : chosen_cells){ + Pose p; + p.x_ = c.first*resolution_ + resolution_*rand()/RAND_MAX + origin_x_; + p.y_ = c.second*resolution_ + resolution_*rand()/RAND_MAX + origin_y_; + p.t_ = 2*M_PI*rand()/RAND_MAX - M_PI; + result.push_back(p); + } +} + +} diff --git a/src/emcl2/src/Mcl.cpp b/src/emcl2/src/Mcl.cpp new file mode 100644 index 0000000..9170dc5 --- /dev/null +++ b/src/emcl2/src/Mcl.cpp @@ -0,0 +1,270 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. +#include "emcl/Mcl.h" +#include +#include +#include +#include + +namespace emcl2 { + +Mcl::Mcl(const Pose &p, int num, const Scan &scan, + const std::shared_ptr &odom_model, + const std::shared_ptr &map) + : last_odom_(NULL), prev_odom_(NULL) +{ + odom_model_ = move(odom_model); + map_ = move(map); + scan_ = scan; + + if(num <= 0) + ROS_ERROR("NO PARTICLE"); + + Particle particle(p.x_, p.y_, p.t_, 1.0/num); + for(int i=0; i accum; + accum.push_back(particles_[0].w_); + for(int i=1;i old(particles_); + + double start = (double)rand()/(RAND_MAX * particles_.size()); + double step = 1.0/particles_.size(); + + std::vector chosen; + + int tick = 0; + for(int i=0; i open_space_threshold_){ + ROS_INFO("RESET"); + expansionReset(); + for(auto &p : particles_) + p.w_ *= p.likelihood(map_.get(), scan); + } + */ + + if(normalizeBelief() > 0.000001) + resampling(); + else + resetWeight(); + + processed_seq_ = scan_.seq_; +} + +void Mcl::motionUpdate(double x, double y, double t) +{ + if(last_odom_ == NULL){ + last_odom_ = new Pose(x, y, t); + prev_odom_ = new Pose(x, y, t); + return; + }else + last_odom_->set(x, y, t); + + Pose d = *last_odom_ - *prev_odom_; + if(d.nearlyZero()) + return; + + double fw_length = sqrt(d.x_*d.x_ + d.y_*d.y_); + double fw_direction = atan2(d.y_, d.x_) - prev_odom_->t_; + + odom_model_->setDev(fw_length, d.t_); + + for(auto &p : particles_) + p.p_.move(fw_length, fw_direction, d.t_, + odom_model_->drawFwNoise(), odom_model_->drawRotNoise()); + + prev_odom_->set(*last_odom_); +} + +void Mcl::meanPose(double &x_mean, double &y_mean, double &t_mean, + double &x_dev, double &y_dev, double &t_dev, + double &xy_cov, double &yt_cov, double &tx_cov) +{ + double x, y, t, t2; + x = y = t = t2 = 0.0; + for(const auto &p : particles_){ + x += p.p_.x_; + y += p.p_.y_; + t += p.p_.t_; + t2 += normalizeAngle(p.p_.t_ + M_PI); + } + + x_mean = x / particles_.size(); + y_mean = y / particles_.size(); + t_mean = t / particles_.size(); + double t2_mean = t2 / particles_.size(); + + double xx, yy, tt, tt2; + xx = yy = tt = tt2 = 0.0; + for(const auto &p : particles_){ + xx += pow(p.p_.x_ - x_mean, 2); + yy += pow(p.p_.y_ - y_mean, 2); + tt += pow(p.p_.t_ - t_mean, 2); + tt2 += pow(normalizeAngle(p.p_.t_ + M_PI) - t2_mean, 2); + } + + if(tt > tt2){ + tt = tt2; + t_mean = normalizeAngle(t2_mean - M_PI); + } + + x_dev = xx/(particles_.size() - 1); + y_dev = yy/(particles_.size() - 1); + t_dev = tt/(particles_.size() - 1); + + double xy, yt, tx; + xy = yt = tx = 0.0; + for(const auto &p : particles_){ + xy += (p.p_.x_ - x_mean)*(p.p_.y_ - y_mean); + yt += (p.p_.y_ - y_mean)*(normalizeAngle(p.p_.t_ - t_mean)); + tx += (p.p_.x_ - x_mean)*(normalizeAngle(p.p_.t_ - t_mean)); + } + + xy_cov = xy/(particles_.size() - 1); + yt_cov = yt/(particles_.size() - 1); + tx_cov = tx/(particles_.size() - 1); +} + +double Mcl::normalizeAngle(double t) +{ + while(t > M_PI) + t -= 2*M_PI; + while(t < -M_PI) + t += 2*M_PI; + + return t; +} + +void Mcl::setScan(const sensor_msgs::LaserScan::ConstPtr &msg) +{ + if(msg->ranges.size() != scan_.ranges_.size()) + scan_.ranges_.resize(msg->ranges.size()); + + scan_.seq_ = msg->header.seq; + for(int i=0; iranges.size(); i++) + scan_.ranges_[i] = msg->ranges[i]; + + scan_.angle_min_ = msg->angle_min; + scan_.angle_max_ = msg->angle_max; + scan_.angle_increment_ = msg->angle_increment; + scan_.range_min_= msg->range_min; + scan_.range_max_= msg->range_max; +} + +double Mcl::normalizeBelief(void) +{ + double sum = 0.0; + for(const auto &p : particles_) + sum += p.w_; + + if(sum < 0.000000000001) + return sum; + + for(auto &p : particles_) + p.w_ /= sum; + + return sum; +} + +void Mcl::resetWeight(void) +{ + for(auto &p : particles_) + p.w_ = 1.0/particles_.size(); +} + +void Mcl::initialize(double x, double y, double t) +{ + Pose new_pose(x, y, t); + for(auto &p : particles_) + p.p_ = new_pose; + + resetWeight(); +} + +void Mcl::simpleReset(void) +{ + std::vector poses; + map_->drawFreePoses(particles_.size(), poses); + + for(int i=0; i +#include +#include +#include + +namespace emcl2 { + +OdomModel::OdomModel(double ff, double fr, double rf, double rr) + : std_norm_dist_(0.0, 1.0), fw_dev_(0.0), rot_dev_(0.0), engine_(seed_gen_()) +{ + fw_var_per_fw_ = ff*ff; + fw_var_per_rot_ = fr*fr; + rot_var_per_fw_ = rf*rf; + rot_var_per_rot_ = rr*rr; +} + +void OdomModel::setDev(double length, double angle) +{ + fw_dev_ = sqrt( fabs(length)*fw_var_per_fw_ + fabs(angle)*fw_var_per_rot_ ); + rot_dev_ = sqrt( fabs(length)*rot_var_per_fw_ + fabs(angle)*rot_var_per_rot_ ); +} + +double OdomModel::drawFwNoise(void) +{ + return std_norm_dist_(engine_) * fw_dev_; +} + +double OdomModel::drawRotNoise(void) +{ + return std_norm_dist_(engine_) * rot_dev_; +} + +} diff --git a/src/emcl2/src/Particle.cpp b/src/emcl2/src/Particle.cpp new file mode 100644 index 0000000..1500ab1 --- /dev/null +++ b/src/emcl2/src/Particle.cpp @@ -0,0 +1,145 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. + +#include "emcl/Particle.h" +#include "emcl/Mcl.h" +#include + +namespace emcl2 { + + + +Particle::Particle(double x, double y, double t, double w) : p_(x, y, t) +{ + w_ = w; +} + +double Particle::likelihood(LikelihoodFieldMap *map, Scan &scan) +{ + uint16_t t = p_.get16bitRepresentation(); + double lidar_x = p_.x_ + scan.lidar_pose_x_*Mcl::cos_[t] + - scan.lidar_pose_y_*Mcl::sin_[t]; + double lidar_y = p_.y_ + scan.lidar_pose_x_*Mcl::sin_[t] + + scan.lidar_pose_y_*Mcl::cos_[t]; + uint16_t lidar_yaw = Pose::get16bitRepresentation(scan.lidar_pose_yaw_); + + double ans = 0.0; + for(int i=0;ilikelihood(lx, ly); + } + return ans; +} + +bool Particle::wallConflict(LikelihoodFieldMap *map, Scan &scan, double threshold, bool replace) +{ + uint16_t t = p_.get16bitRepresentation(); + double lidar_x = p_.x_ + scan.lidar_pose_x_*Mcl::cos_[t] + - scan.lidar_pose_y_*Mcl::sin_[t]; + double lidar_y = p_.y_ + scan.lidar_pose_x_*Mcl::sin_[t] + + scan.lidar_pose_y_*Mcl::cos_[t]; + uint16_t lidar_yaw = Pose::get16bitRepresentation(scan.lidar_pose_yaw_); + + std::vector order; + if(rand()%2){ + for(int i=0;i=0;i-=scan.scan_increment_) + order.push_back(i); + } + + int hit_counter = 0; + for(int i : order){ + if(not scan.valid(scan.ranges_[i])) + continue; + + double range = scan.ranges_[i]; + uint16_t a = scan.directions_16bit_[i] + t + lidar_yaw; + + double hit_lx, hit_ly; + double hit_lx1, hit_ly1, r1; + uint16_t a1; + if(isPenetrating(lidar_x, lidar_y, range, a, map, hit_lx, hit_ly)){ + if(hit_counter == 0){ + hit_lx1 = hit_lx; + hit_ly1 = hit_ly; + r1 = range; + a1 = a; + } + + hit_counter++; + }else + hit_counter = 0; + + if(hit_counter*scan.angle_increment_ >= threshold){ + if(replace) + sensorReset(lidar_x, lidar_y, + r1, a1, hit_lx1, hit_ly1, + range, a, hit_lx, hit_ly); + return true; + } + } + return false; +} + +bool Particle::isPenetrating(double ox, double oy, double range, uint16_t direction, + LikelihoodFieldMap *map, double &hit_lx, double &hit_ly) +{ + bool hit = false; + for(double d=map->resolution_;dresolution_){ + double lx = ox + d * Mcl::cos_[direction]; + double ly = oy + d * Mcl::sin_[direction]; + + if((not hit) and map->likelihood(lx, ly) > 0.99){ + hit = true; + hit_lx = lx; + hit_ly = ly; + } + else if(hit and map->likelihood(lx, ly) == 0.0){ // openspace after hit + return true; // penetration + } + } + return false; +} + +void Particle::sensorReset(double ox, double oy, + double range1, uint16_t direction1, double hit_lx1, double hit_ly1, + double range2, uint16_t direction2, double hit_lx2, double hit_ly2) +{ + double p1_x = ox + range1 * Mcl::cos_[direction1]; + double p1_y = oy + range1 * Mcl::sin_[direction1]; + double p2_x = ox + range2 * Mcl::cos_[direction2]; + double p2_y = oy + range2 * Mcl::sin_[direction2]; + + double cx = (hit_lx1 + hit_lx2)/2; + double cy = (hit_ly1 + hit_ly2)/2; + + p_.x_ -= (p1_x + p2_x)/2 - cx; + p_.y_ -= (p1_y + p2_y)/2 - cy; + + double theta_delta = atan2(p2_y - p1_y, p2_x - p1_x) - atan2(hit_ly2 - hit_ly1, hit_lx2 - hit_lx1); + /* + double d = std::sqrt((p_.x_ - cx)*(p_.x_ - cx) + (p_.y_ - cy)*(p_.y_ - cy)); + + double theta = atan2(p_.y_ - cy, p_.x_ - cx) - theta_delta; + p_.x_ = cx + d * std::cos(theta); + p_.y_ = cy + d * std::cos(theta); +*/ + p_.t_ -= theta_delta; +} + +Particle Particle::operator =(const Particle &p) +{ + p_ = p.p_; + w_ = p.w_; + return *this; +} + +} diff --git a/src/emcl2/src/Pose.cpp b/src/emcl2/src/Pose.cpp new file mode 100644 index 0000000..5402e49 --- /dev/null +++ b/src/emcl2/src/Pose.cpp @@ -0,0 +1,97 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. + +#include "emcl/Pose.h" +#include +#include + +namespace emcl2 { + +Pose::Pose(double x, double y, double t) +{ + set(x, y, t); +} + +void Pose::set(double x, double y, double t) +{ + x_ = x; + y_ = y; + t_ = t; +} + +void Pose::set(const Pose &p) +{ + x_ = p.x_; + y_ = p.y_; + t_ = p.t_; +} + +std::string Pose::to_s(void) +{ + std::stringstream s; + s << "x:" << x_ << "\ty:" << y_ << "\tt:" << t_; + return s.str(); +} + +void Pose::normalizeAngle(void) +{ + while(t_ > M_PI) + t_ -= 2*M_PI; + while(t_ < -M_PI) + t_ += 2*M_PI; +} + +Pose Pose::operator -(const Pose &p) const +{ + Pose ans(x_ - p.x_, y_ - p.y_, t_ - p.t_); + ans.normalizeAngle(); + + return ans; +} + +Pose Pose::operator =(const Pose &p) +{ + x_ = p.x_; + y_ = p.y_; + t_ = p.t_; + return *this; +} + +void Pose::move(double length, double direction, double rotation, + double fw_noise, double rot_noise) +{ + x_ += (length + fw_noise)*cos(direction + rot_noise + t_); + y_ += (length + fw_noise)*sin(direction + rot_noise + t_); + t_ += rotation + rot_noise; + normalizeAngle(); +} + +bool Pose::nearlyZero(void) +{ + return fabs(x_) < 0.001 and fabs(y_) < 0.001 and fabs(t_) < 0.001; +} + +uint16_t Pose::get16bitRepresentation(void) +{ + int tmp = t_/M_PI*(1<<15); + while(tmp < 0) + tmp += (1<<16); + while(tmp >= (1<<16)) + tmp -= (1<<16); + + return (uint16_t)tmp; +} + +uint16_t Pose::get16bitRepresentation(double t) +{ + int tmp = t/M_PI*(1<<15); + while(tmp < 0) + tmp += (1<<16); + while(tmp >= (1<<16)) + tmp -= (1<<16); + + return (uint16_t)tmp; +} + +} diff --git a/src/emcl2/src/Scan.cpp b/src/emcl2/src/Scan.cpp new file mode 100644 index 0000000..b9fcc89 --- /dev/null +++ b/src/emcl2/src/Scan.cpp @@ -0,0 +1,51 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. + +#include "emcl/Scan.h" +#include + +namespace emcl2 { + +Scan& Scan::operator=(const Scan &s) +{ + if(this == &s) + return *this; + + seq_ = s.seq_; + scan_increment_ = s.scan_increment_; + angle_max_ = s.angle_max_; + angle_min_ = s.angle_min_; + angle_increment_ = s.angle_increment_; + range_max_ = s.range_max_; + range_min_ = s.range_min_; + + // It's not thread safe. + ranges_.clear(); + copy(s.ranges_.begin(), s.ranges_.end(), back_inserter(ranges_) ); + + return *this; +} + +int Scan::countValidBeams(double *rate) +{ + int ans = 0; + for(int i=0; i("particlecloud", 2, true); + pose_pub_ = nh_.advertise("mcl_pose", 2, true); + alpha_pub_ = nh_.advertise("alpha", 2, true); + laser_scan_sub_ = nh_.subscribe("scan", 2, &EMcl2Node::cbScan, this); + initial_pose_sub_ = nh_.subscribe("initialpose", 2, &EMcl2Node::initialPoseReceived, this); + + global_loc_srv_ = nh_.advertiseService("global_localization", &EMcl2Node::cbSimpleReset, this); + + private_nh_.param("global_frame_id", global_frame_id_, std::string("map")); + private_nh_.param("footprint_frame_id", footprint_frame_id_, std::string("base_footprint")); + private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom")); + private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link")); + + tfb_.reset(new tf2_ros::TransformBroadcaster()); + tf_.reset(new tf2_ros::Buffer()); + tfl_.reset(new tf2_ros::TransformListener(*tf_)); +} + +void EMcl2Node::initPF(void) +{ + std::shared_ptr map = std::move(initMap()); + std::shared_ptr om = std::move(initOdometry()); + + Scan scan; + private_nh_.param("laser_min_range", scan.range_min_, 0.0); + private_nh_.param("laser_max_range", scan.range_max_, 100000000.0); + private_nh_.param("scan_increment", scan.scan_increment_, 1); + + Pose init_pose; + private_nh_.param("initial_pose_x", init_pose.x_, 0.0); + private_nh_.param("initial_pose_y", init_pose.y_, 0.0); + private_nh_.param("initial_pose_a", init_pose.t_, 0.0); + + int num_particles; + double alpha_th; + double ex_rad_pos, ex_rad_ori; + private_nh_.param("num_particles", num_particles, 0); + private_nh_.param("alpha_threshold", alpha_th, 0.5); + private_nh_.param("expansion_radius_position", ex_rad_pos, 0.1); + private_nh_.param("expansion_radius_orientation", ex_rad_ori, 0.2); + + double extraction_rate, range_threshold; + bool sensor_reset; + private_nh_.param("extraction_rate", extraction_rate, 0.1); + private_nh_.param("range_threshold", range_threshold, 0.1); + private_nh_.param("sensor_reset", sensor_reset, true); + + pf_.reset(new ExpResetMcl2(init_pose, num_particles, scan, om, map, + alpha_th, ex_rad_pos, ex_rad_ori, + extraction_rate, range_threshold, sensor_reset)); +} + +std::shared_ptr EMcl2Node::initOdometry(void) +{ + double ff, fr, rf, rr; + private_nh_.param("odom_fw_dev_per_fw", ff, 0.19); + private_nh_.param("odom_fw_dev_per_rot", fr, 0.0001); + private_nh_.param("odom_rot_dev_per_fw", rf, 0.13); + private_nh_.param("odom_rot_dev_per_rot", rr, 0.2); + return std::shared_ptr(new OdomModel(ff, fr, rf, rr)); +} + +std::shared_ptr EMcl2Node::initMap(void) +{ + double likelihood_range; + private_nh_.param("laser_likelihood_max_dist", likelihood_range, 0.2); + + int num; + private_nh_.param("num_particles", num, 0); + + nav_msgs::GetMap::Request req; + nav_msgs::GetMap::Response resp; + ROS_INFO("Requesting the map..."); + while(!ros::service::call("static_map", req, resp)){ + ROS_WARN("Request for map failed; trying again..."); + ros::Duration d(0.5); + d.sleep(); + } + + return std::shared_ptr(new LikelihoodFieldMap(resp.map, likelihood_range)); +} + +void EMcl2Node::cbScan(const sensor_msgs::LaserScan::ConstPtr &msg) +{ + scan_frame_id_ = msg->header.frame_id; + pf_->setScan(msg); +} + +void EMcl2Node::initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg) +{ + init_request_ = true; + init_x_ = msg->pose.pose.position.x; + init_y_ = msg->pose.pose.position.y; + init_t_ = tf2::getYaw(msg->pose.pose.orientation); +} + +void EMcl2Node::loop(void) +{ + if(init_request_){ + pf_->initialize(init_x_, init_y_, init_t_); + init_request_ = false; + } + else if(simple_reset_request_){ + pf_->simpleReset(); + simple_reset_request_ = false; + } + + double x, y, t; + if(not getOdomPose(x, y, t)){ + ROS_INFO("can't get odometry info"); + return; + } + pf_->motionUpdate(x, y, t); + + double lx, ly, lt; + bool inv; + if(not getLidarPose(lx, ly, lt, inv)){ + ROS_INFO("can't get lidar pose info"); + return; + } + + /* + struct timespec ts_start, ts_end; + clock_gettime(CLOCK_REALTIME, &ts_start); + */ + pf_->sensorUpdate(lx, ly, lt, inv); + /* + clock_gettime(CLOCK_REALTIME, &ts_end); + struct tm tm; + localtime_r( &ts_start.tv_sec, &tm); + printf("START: %02d.%09ld\n", tm.tm_sec, ts_start.tv_nsec); + localtime_r( &ts_end.tv_sec, &tm); + printf("END: %02d.%09ld\n", tm.tm_sec, ts_end.tv_nsec); + */ + + double x_var, y_var, t_var, xy_cov, yt_cov, tx_cov; + pf_->meanPose(x, y, t, x_var, y_var, t_var, xy_cov, yt_cov, tx_cov); + + publishOdomFrame(x, y, t); + publishPose(x, y, t, x_var, y_var, t_var, xy_cov, yt_cov, tx_cov); + publishParticles(); + + std_msgs::Float32 alpha_msg; + alpha_msg.data = static_cast(pf_->alpha_); + alpha_pub_.publish(alpha_msg); +} + +void EMcl2Node::publishPose(double x, double y, double t, + double x_dev, double y_dev, double t_dev, + double xy_cov, double yt_cov, double tx_cov) +{ + geometry_msgs::PoseWithCovarianceStamped p; + p.header.frame_id = global_frame_id_; + p.header.stamp = ros::Time::now(); + p.pose.pose.position.x = x; + p.pose.pose.position.y = y; + + p.pose.covariance[6*0 + 0] = x_dev; + p.pose.covariance[6*1 + 1] = y_dev; + p.pose.covariance[6*2 + 2] = t_dev; + + p.pose.covariance[6*0 + 1] = xy_cov; + p.pose.covariance[6*1 + 0] = xy_cov; + p.pose.covariance[6*0 + 2] = tx_cov; + p.pose.covariance[6*2 + 0] = tx_cov; + p.pose.covariance[6*1 + 2] = yt_cov; + p.pose.covariance[6*2 + 1] = yt_cov; + + tf2::Quaternion q; + q.setRPY(0, 0, t); + tf2::convert(q, p.pose.pose.orientation); + + pose_pub_.publish(p); +} + +void EMcl2Node::publishOdomFrame(double x, double y, double t) +{ + geometry_msgs::PoseStamped odom_to_map; + try{ + tf2::Quaternion q; + q.setRPY(0, 0, t); + tf2::Transform tmp_tf(q, tf2::Vector3(x, y, 0.0)); + + geometry_msgs::PoseStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = footprint_frame_id_; + tmp_tf_stamped.header.stamp = ros::Time(0); + tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose); + + tf_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_); + + }catch(tf2::TransformException){ + ROS_DEBUG("Failed to subtract base to odom transform"); + return; + } + tf2::convert(odom_to_map.pose, latest_tf_); + + ros::Time transform_expiration = (ros::Time(ros::Time::now().toSec() + 0.2)); + geometry_msgs::TransformStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = global_frame_id_; + tmp_tf_stamped.header.stamp = transform_expiration; + tmp_tf_stamped.child_frame_id = odom_frame_id_; + tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform); + + tfb_->sendTransform(tmp_tf_stamped); +} + +void EMcl2Node::publishParticles(void) +{ + geometry_msgs::PoseArray cloud_msg; + cloud_msg.header.stamp = ros::Time::now(); + cloud_msg.header.frame_id = global_frame_id_; + cloud_msg.poses.resize(pf_->particles_.size()); + + for(int i=0;iparticles_.size();i++){ + cloud_msg.poses[i].position.x = pf_->particles_[i].p_.x_; + cloud_msg.poses[i].position.y = pf_->particles_[i].p_.y_; + cloud_msg.poses[i].position.z = 0; + + tf2::Quaternion q; + q.setRPY(0, 0, pf_->particles_[i].p_.t_); + tf2::convert(q, cloud_msg.poses[i].orientation); + } + particlecloud_pub_.publish(cloud_msg); +} + +bool EMcl2Node::getOdomPose(double& x, double& y, double& yaw) +{ + geometry_msgs::PoseStamped ident; + ident.header.frame_id = footprint_frame_id_; + ident.header.stamp = ros::Time(0); + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + + geometry_msgs::PoseStamped odom_pose; + try{ + this->tf_->transform(ident, odom_pose, odom_frame_id_); + }catch(tf2::TransformException e){ + ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what()); + return false; + } + x = odom_pose.pose.position.x; + y = odom_pose.pose.position.y; + yaw = tf2::getYaw(odom_pose.pose.orientation); + + return true; +} + +bool EMcl2Node::getLidarPose(double& x, double& y, double& yaw, bool& inv) +{ + geometry_msgs::PoseStamped ident; + ident.header.frame_id = scan_frame_id_; + ident.header.stamp = ros::Time(0); + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + + geometry_msgs::PoseStamped lidar_pose; + try{ + this->tf_->transform(ident, lidar_pose, base_frame_id_); + }catch(tf2::TransformException e){ + ROS_WARN("Failed to compute lidar pose, skipping scan (%s)", e.what()); + return false; + } + x = lidar_pose.pose.position.x; + y = lidar_pose.pose.position.y; + + double roll, pitch; + tf2::getEulerYPR(lidar_pose.pose.orientation, yaw, pitch, roll); + inv = (fabs(pitch) > M_PI/2 || fabs(roll) > M_PI/2) ? true : false; + + return true; +} + +int EMcl2Node::getOdomFreq(void){ + return odom_freq_; +} + +bool EMcl2Node::cbSimpleReset(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) +{ + return simple_reset_request_ = true; +} + +} + +int main(int argc, char **argv) +{ + + ros::init(argc, argv, "mcl_node"); + emcl2::EMcl2Node node; + + ros::Rate loop_rate(node.getOdomFreq()); + while (ros::ok()){ + node.loop(); + ros::spinOnce(); + loop_rate.sleep(); + } + + ros::spin(); + + return 0; +} + diff --git a/src/emcl2/test/docker/Dockerfile b/src/emcl2/test/docker/Dockerfile new file mode 100644 index 0000000..f66d956 --- /dev/null +++ b/src/emcl2/test/docker/Dockerfile @@ -0,0 +1,10 @@ +FROM ryuichiueda/emcl-test-env:latest +ENV DEBIAN_FRONTEND=noninteractive +SHELL ["/bin/bash", "-c"] + +RUN cd /catkin_ws/src && \ + git clone https://github.com/ryuichiueda/emcl.git + +RUN source ~/.bashrc && \ + cd /catkin_ws && \ + catkin_make diff --git a/src/emcl2/test/docker_env/Dockerfile b/src/emcl2/test/docker_env/Dockerfile new file mode 100644 index 0000000..fb904b0 --- /dev/null +++ b/src/emcl2/test/docker_env/Dockerfile @@ -0,0 +1,17 @@ +FROM ryuichiueda/ubuntu18.04-ros-image +ENV DEBIAN_FRONTEND=noninteractive +SHELL ["/bin/bash", "-c"] + +RUN apt-get update +RUN apt-get install -y ros-melodic-desktop-full +RUN apt-get install -y ros-melodic-tf ros-melodic-tf2 ros-melodic-tf2-geometry-msgs ros-melodic-urdf ros-melodic-map-server xvfb vim psmisc ros-melodic-move-base* ros-melodic-dwa-local-planner ros-melodic-global-planner ros-melodic-grid-map + +RUN cd /catkin_ws/src && \ + git clone https://github.com/ROBOTIS-GIT/turtlebot3.git && \ + git clone https://github.com/ROBOTIS-GIT/turtlebot3_gazebo_plugin.git && \ + git clone https://github.com/ROBOTIS-GIT/turtlebot3_msgs.git && \ + git clone https://github.com/ROBOTIS-GIT/turtlebot3_simulations.git + +RUN source ~/.bashrc && \ + cd /catkin_ws && \ + catkin_make diff --git a/src/emcl2/test/test.bash b/src/emcl2/test/test.bash new file mode 100755 index 0000000..ad9bf64 --- /dev/null +++ b/src/emcl2/test/test.bash @@ -0,0 +1,76 @@ +#!/bin/bash -evx + +export TURTLEBOT3_MODEL=burger +xvfb-run --auto-servernum -s "-screen 0 1400x900x24" roslaunch emcl2 test.launch & +sleep 15 + +### ESTIMATION RECOVERY TEST ### +rostopic pub /initialpose geometry_msgs/PoseWithCovarianceStamped "header: + seq: 0 + stamp: + secs: 0 + nsecs: 0 + frame_id: '' +pose: + pose: + position: {x: -2.5, y: 0.0, z: 0.0} + orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0} + covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" --once + +rostopic echo /mcl_pose -n 1000 | +grep -A2 position: | +awk '/x:/{printf $2" "}/y:/{print $2}' | +awk '{print $0} + sqrt( ($1+2.0)^2 + ($2+0.5)^2 ) < 0.15 {print "OK";exit(0)} + NR==1000{print "TIMEOUT";exit(1)}' + +if [ "$?" -ne 0 ] ; then + killall rosmaster & + exit 1 +fi + +### NAVIGATION TEST ### +rostopic pub /move_base/goal move_base_msgs/MoveBaseActionGoal "header: + seq: 0 + stamp: + secs: 0 + nsecs: 0 + frame_id: 'map' +goal_id: + stamp: + secs: 0 + nsecs: 0 + id: '' +goal: + target_pose: + header: + seq: 0 + stamp: + secs: 0 + nsecs: 0 + frame_id: 'map' + pose: + position: + x: -0.5 + y: -0.5 + z: 0.0 + orientation: + x: 0.0 + y: 0.0 + z: 0.0 + w: 0.1" --once + +rostopic echo /mcl_pose -n 1000 | +grep -A2 position: | +awk '/x:/{printf $2" "}/y:/{print $2}' | +awk '{print $0} + sqrt( ($1+0.5)^2 + ($2+0.5)^2 ) < 0.15 {print "OK";exit(0)} + NR==1000{print "TIMEOUT";exit(1)}' + +RESULT=$? + +killall rosmaster & + +exit $RESULT diff --git a/src/emcl2/test/test.launch b/src/emcl2/test/test.launch new file mode 100644 index 0000000..0f534c2 --- /dev/null +++ b/src/emcl2/test/test.launch @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/emcl2/test/test_gui.bash b/src/emcl2/test/test_gui.bash new file mode 100755 index 0000000..43c40f5 --- /dev/null +++ b/src/emcl2/test/test_gui.bash @@ -0,0 +1,76 @@ +#!/bin/bash -evx + +export TURTLEBOT3_MODEL=burger +roslaunch emcl test_gui.launch & +sleep 15 + +### ESTIMATION RECOVERY TEST ### +rostopic pub /initialpose geometry_msgs/PoseWithCovarianceStamped "header: + seq: 0 + stamp: + secs: 0 + nsecs: 0 + frame_id: '' +pose: + pose: + position: {x: -2.5, y: 0.0, z: 0.0} + orientation: {x: 0.0, y: 0.0, z: 0.0, w: 0.0} + covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]" --once + +rostopic echo /mcl_pose -n 1000 | +grep -A2 position: | +awk '/x:/{printf $2" "}/y:/{print $2}' | +awk '{print $0} + sqrt( ($1+2.0)^2 + ($2+0.5)^2 ) < 0.15 {print "OK";exit(0)} + NR==1000{print "TIMEOUT";exit(1)}' + +if [ "$?" -ne 0 ] ; then + killall rosmaster & + exit 1 +fi + +### NAVIGATION TEST ### +rostopic pub /move_base/goal move_base_msgs/MoveBaseActionGoal "header: + seq: 0 + stamp: + secs: 0 + nsecs: 0 + frame_id: 'map' +goal_id: + stamp: + secs: 0 + nsecs: 0 + id: '' +goal: + target_pose: + header: + seq: 0 + stamp: + secs: 0 + nsecs: 0 + frame_id: 'map' + pose: + position: + x: -0.5 + y: -0.5 + z: 0.0 + orientation: + x: 0.0 + y: 0.0 + z: 0.0 + w: 0.1" --once + +rostopic echo /mcl_pose -n 1000 | +grep -A2 position: | +awk '/x:/{printf $2" "}/y:/{print $2}' | +awk '{print $0} + sqrt( ($1+0.5)^2 + ($2+0.5)^2 ) < 0.15 {print "OK";exit(0)} + NR==1000{print "TIMEOUT";exit(1)}' + +RESULT=$? + +killall rosmaster & + +exit $RESULT diff --git a/src/emcl2/test/test_gui.launch b/src/emcl2/test/test_gui.launch new file mode 100644 index 0000000..654ba35 --- /dev/null +++ b/src/emcl2/test/test_gui.launch @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/emcl2/trash/emcl_node.cpp b/src/emcl2/trash/emcl_node.cpp new file mode 100644 index 0000000..49c1da8 --- /dev/null +++ b/src/emcl2/trash/emcl_node.cpp @@ -0,0 +1,324 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. + +#include "emcl/emcl_node.h" +#include "emcl/Pose.h" + +#include "tf2/utils.h" +#include "geometry_msgs/PoseArray.h" +#include "nav_msgs/GetMap.h" +#include "std_msgs/Float32.h" + +namespace emcl2 { + +EMclNode::EMclNode() : private_nh_("~") +{ + initCommunication(); + initPF(); + + private_nh_.param("odom_freq", odom_freq_, 20); + + init_request_ = false; + simple_reset_request_ = false; +} + +EMclNode::~EMclNode() +{ +} + +void EMclNode::initCommunication(void) +{ + particlecloud_pub_ = nh_.advertise("particlecloud", 2, true); + pose_pub_ = nh_.advertise("mcl_pose", 2, true); + alpha_pub_ = nh_.advertise("alpha", 2, true); + laser_scan_sub_ = nh_.subscribe("scan", 2, &EMclNode::cbScan, this); + initial_pose_sub_ = nh_.subscribe("initialpose", 2, &EMclNode::initialPoseReceived, this); + + global_loc_srv_ = nh_.advertiseService("global_localization", &EMclNode::cbSimpleReset, this); + + private_nh_.param("global_frame_id", global_frame_id_, std::string("map")); + private_nh_.param("footprint_frame_id", footprint_frame_id_, std::string("base_footprint")); + private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom")); + private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link")); + + tfb_.reset(new tf2_ros::TransformBroadcaster()); + tf_.reset(new tf2_ros::Buffer()); + tfl_.reset(new tf2_ros::TransformListener(*tf_)); +} + +void EMclNode::initPF(void) +{ + std::shared_ptr map = std::move(initMap()); + std::shared_ptr om = std::move(initOdometry()); + + Scan scan; + private_nh_.param("laser_min_range", scan.range_min_, 0.0); + private_nh_.param("laser_max_range", scan.range_max_, 100000000.0); + private_nh_.param("scan_increment", scan.scan_increment_, 1); + + Pose init_pose; + private_nh_.param("initial_pose_x", init_pose.x_, 0.0); + private_nh_.param("initial_pose_y", init_pose.y_, 0.0); + private_nh_.param("initial_pose_a", init_pose.t_, 0.0); + + int num_particles; + double alpha_th, open_space_th; + double ex_rad_pos, ex_rad_ori; + private_nh_.param("num_particles", num_particles, 0); + private_nh_.param("alpha_threshold", alpha_th, 0.0); + private_nh_.param("open_space_threshold", open_space_th, 0.05); + private_nh_.param("expansion_radius_position", ex_rad_pos, 0.1); + private_nh_.param("expansion_radius_orientation", ex_rad_ori, 0.2); + + pf_.reset(new ExpResetMcl(init_pose, num_particles, scan, om, map, + alpha_th, open_space_th, ex_rad_pos, ex_rad_ori)); +} + +std::shared_ptr EMclNode::initOdometry(void) +{ + double ff, fr, rf, rr; + private_nh_.param("odom_fw_dev_per_fw", ff, 0.19); + private_nh_.param("odom_fw_dev_per_rot", fr, 0.0001); + private_nh_.param("odom_rot_dev_per_fw", rf, 0.13); + private_nh_.param("odom_rot_dev_per_rot", rr, 0.2); + return std::shared_ptr(new OdomModel(ff, fr, rf, rr)); +} + +std::shared_ptr EMclNode::initMap(void) +{ + double likelihood_range; + private_nh_.param("laser_likelihood_max_dist", likelihood_range, 0.2); + + int num; + private_nh_.param("num_particles", num, 0); + + nav_msgs::GetMap::Request req; + nav_msgs::GetMap::Response resp; + ROS_INFO("Requesting the map..."); + while(!ros::service::call("static_map", req, resp)){ + ROS_WARN("Request for map failed; trying again..."); + ros::Duration d(0.5); + d.sleep(); + } + + return std::shared_ptr(new LikelihoodFieldMap(resp.map, likelihood_range)); +} + +void EMclNode::cbScan(const sensor_msgs::LaserScan::ConstPtr &msg) +{ + scan_frame_id_ = msg->header.frame_id; + pf_->setScan(msg); +} + +void EMclNode::initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg) +{ + init_request_ = true; + init_x_ = msg->pose.pose.position.x; + init_y_ = msg->pose.pose.position.y; + init_t_ = tf2::getYaw(msg->pose.pose.orientation); +} + +void EMclNode::loop(void) +{ + if(init_request_){ + pf_->initialize(init_x_, init_y_, init_t_); + init_request_ = false; + } + else if(simple_reset_request_){ + pf_->simpleReset(); + simple_reset_request_ = false; + } + + double x, y, t; + if(not getOdomPose(x, y, t)){ + ROS_INFO("can't get odometry info"); + return; + } + pf_->motionUpdate(x, y, t); + + double lx, ly, lt; + bool inv; + if(not getLidarPose(lx, ly, lt, inv)){ + ROS_INFO("can't get lidar pose info"); + return; + } + + /* + struct timespec ts_start, ts_end; + clock_gettime(CLOCK_REALTIME, &ts_start); + */ + pf_->sensorUpdate(lx, ly, lt, inv); + /* + clock_gettime(CLOCK_REALTIME, &ts_end); + struct tm tm; + localtime_r( &ts_start.tv_sec, &tm); + printf("START: %02d.%09ld\n", tm.tm_sec, ts_start.tv_nsec); + localtime_r( &ts_end.tv_sec, &tm); + printf("END: %02d.%09ld\n", tm.tm_sec, ts_end.tv_nsec); + */ + + double x_var, y_var, t_var, xy_cov, yt_cov, tx_cov; + pf_->meanPose(x, y, t, x_var, y_var, t_var, xy_cov, yt_cov, tx_cov); + + publishOdomFrame(x, y, t); + publishPose(x, y, t, x_var, y_var, t_var, xy_cov, yt_cov, tx_cov); + publishParticles(); + + std_msgs::Float32 alpha_msg; + alpha_msg.data = static_cast(pf_->alpha_); + alpha_pub_.publish(alpha_msg); +} + +void EMclNode::publishPose(double x, double y, double t, + double x_dev, double y_dev, double t_dev, + double xy_cov, double yt_cov, double tx_cov) +{ + geometry_msgs::PoseWithCovarianceStamped p; + p.header.frame_id = global_frame_id_; + p.header.stamp = ros::Time::now(); + p.pose.pose.position.x = x; + p.pose.pose.position.y = y; + + p.pose.covariance[6*0 + 0] = x_dev; + p.pose.covariance[6*1 + 1] = y_dev; + p.pose.covariance[6*2 + 2] = t_dev; + + p.pose.covariance[6*0 + 1] = xy_cov; + p.pose.covariance[6*1 + 0] = xy_cov; + p.pose.covariance[6*0 + 2] = tx_cov; + p.pose.covariance[6*2 + 0] = tx_cov; + p.pose.covariance[6*1 + 2] = yt_cov; + p.pose.covariance[6*2 + 1] = yt_cov; + + tf2::Quaternion q; + q.setRPY(0, 0, t); + tf2::convert(q, p.pose.pose.orientation); + + pose_pub_.publish(p); +} + +void EMclNode::publishOdomFrame(double x, double y, double t) +{ + geometry_msgs::PoseStamped odom_to_map; + try{ + tf2::Quaternion q; + q.setRPY(0, 0, t); + tf2::Transform tmp_tf(q, tf2::Vector3(x, y, 0.0)); + + geometry_msgs::PoseStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = footprint_frame_id_; + tmp_tf_stamped.header.stamp = ros::Time(0); + tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose); + + tf_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_); + + }catch(tf2::TransformException){ + ROS_DEBUG("Failed to subtract base to odom transform"); + return; + } + tf2::convert(odom_to_map.pose, latest_tf_); + + ros::Time transform_expiration = (ros::Time(ros::Time::now().toSec() + 0.2)); + geometry_msgs::TransformStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = global_frame_id_; + tmp_tf_stamped.header.stamp = transform_expiration; + tmp_tf_stamped.child_frame_id = odom_frame_id_; + tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform); + + tfb_->sendTransform(tmp_tf_stamped); +} + +void EMclNode::publishParticles(void) +{ + geometry_msgs::PoseArray cloud_msg; + cloud_msg.header.stamp = ros::Time::now(); + cloud_msg.header.frame_id = global_frame_id_; + cloud_msg.poses.resize(pf_->particles_.size()); + + for(int i=0;iparticles_.size();i++){ + cloud_msg.poses[i].position.x = pf_->particles_[i].p_.x_; + cloud_msg.poses[i].position.y = pf_->particles_[i].p_.y_; + cloud_msg.poses[i].position.z = 0; + + tf2::Quaternion q; + q.setRPY(0, 0, pf_->particles_[i].p_.t_); + tf2::convert(q, cloud_msg.poses[i].orientation); + } + particlecloud_pub_.publish(cloud_msg); +} + +bool EMclNode::getOdomPose(double& x, double& y, double& yaw) +{ + geometry_msgs::PoseStamped ident; + ident.header.frame_id = footprint_frame_id_; + ident.header.stamp = ros::Time(0); + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + + geometry_msgs::PoseStamped odom_pose; + try{ + this->tf_->transform(ident, odom_pose, odom_frame_id_); + }catch(tf2::TransformException e){ + ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what()); + return false; + } + x = odom_pose.pose.position.x; + y = odom_pose.pose.position.y; + yaw = tf2::getYaw(odom_pose.pose.orientation); + + return true; +} + +bool EMclNode::getLidarPose(double& x, double& y, double& yaw, bool& inv) +{ + geometry_msgs::PoseStamped ident; + ident.header.frame_id = scan_frame_id_; + ident.header.stamp = ros::Time(0); + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + + geometry_msgs::PoseStamped lidar_pose; + try{ + this->tf_->transform(ident, lidar_pose, base_frame_id_); + }catch(tf2::TransformException e){ + ROS_WARN("Failed to compute lidar pose, skipping scan (%s)", e.what()); + return false; + } + x = lidar_pose.pose.position.x; + y = lidar_pose.pose.position.y; + + double roll, pitch; + tf2::getEulerYPR(lidar_pose.pose.orientation, yaw, pitch, roll); + inv = (fabs(pitch) > M_PI/2 || fabs(roll) > M_PI/2) ? true : false; + + return true; +} + +int EMclNode::getOdomFreq(void){ + return odom_freq_; +} + +bool EMclNode::cbSimpleReset(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) +{ + return simple_reset_request_ = true; +} + +} + +int main(int argc, char **argv) +{ + + ros::init(argc, argv, "mcl_node"); + emcl::EMclNode node; + + ros::Rate loop_rate(node.getOdomFreq()); + while (ros::ok()){ + node.loop(); + ros::spinOnce(); + loop_rate.sleep(); + } + + ros::spin(); + + return 0; +} + diff --git a/src/emcl2/trash/emcl_node.h b/src/emcl2/trash/emcl_node.h new file mode 100644 index 0000000..0c48e19 --- /dev/null +++ b/src/emcl2/trash/emcl_node.h @@ -0,0 +1,80 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef INTERFACE_EMCL_H__ +#define INTERFACE_EMCL_H__ + +#include +#include "emcl/ExpResetMcl.h" + +#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_listener.h" +#include "tf2_ros/message_filter.h" +#include "tf2/LinearMath/Transform.h" + +#include "sensor_msgs/LaserScan.h" +#include "geometry_msgs/PoseWithCovarianceStamped.h" +#include "std_srvs/Empty.h" + +namespace emcl2 { + +class EMclNode +{ +public: + EMclNode(); + ~EMclNode(); + + void loop(void); + int getOdomFreq(void); +private: + std::shared_ptr pf_; + ros::NodeHandle nh_; + ros::NodeHandle private_nh_; + + ros::Publisher particlecloud_pub_; + ros::Publisher pose_pub_; + ros::Publisher alpha_pub_; + ros::Subscriber laser_scan_sub_; + ros::Subscriber initial_pose_sub_; + + ros::ServiceServer global_loc_srv_; + + std::string footprint_frame_id_; + std::string global_frame_id_; + std::string odom_frame_id_; + std::string scan_frame_id_; + std::string base_frame_id_; + + std::shared_ptr tfb_; + std::shared_ptr tfl_; + std::shared_ptr tf_; + + tf2::Transform latest_tf_; + + int odom_freq_; + bool init_request_; + bool simple_reset_request_; + double init_x_, init_y_, init_t_; + + void publishPose(double x, double y, double t, + double x_dev, double y_dev, double t_dev, + double xy_cov, double yt_cov, double tx_cov); + void publishOdomFrame(double x, double y, double t); + void publishParticles(void); + void sendTf(void); + bool getOdomPose(double& x, double& y, double& yaw); + bool getLidarPose(double& x, double& y, double& yaw, bool& inv); + + void initCommunication(void); + void initPF(void); + std::shared_ptr initMap(void); + std::shared_ptr initOdometry(void); + + void cbScan(const sensor_msgs::LaserScan::ConstPtr &msg); + bool cbSimpleReset(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res); + void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg); +}; + +} + +#endif diff --git a/src/emcl2/trash/mcl_node.cpp b/src/emcl2/trash/mcl_node.cpp new file mode 100644 index 0000000..b892b73 --- /dev/null +++ b/src/emcl2/trash/mcl_node.cpp @@ -0,0 +1,317 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later +//Some lines are derived from https://github.com/ros-planning/navigation/tree/noetic-devel/amcl. + +#include "emcl/mcl_node.h" +#include "emcl/Pose.h" + +#include "tf2/utils.h" +#include "geometry_msgs/PoseArray.h" +#include "nav_msgs/GetMap.h" +#include "std_msgs/Float32.h" + +namespace emcl2 { + +MclNode::MclNode() : private_nh_("~") +{ + initCommunication(); + initPF(); + + private_nh_.param("odom_freq", odom_freq_, 20); + + init_request_ = false; + simple_reset_request_ = false; +} + +MclNode::~MclNode() +{ +} + +void MclNode::initCommunication(void) +{ + particlecloud_pub_ = nh_.advertise("particlecloud", 2, true); + pose_pub_ = nh_.advertise("mcl_pose", 2, true); + alpha_pub_ = nh_.advertise("alpha", 2, true); + laser_scan_sub_ = nh_.subscribe("scan", 2, &MclNode::cbScan, this); + initial_pose_sub_ = nh_.subscribe("initialpose", 2, &MclNode::initialPoseReceived, this); + + global_loc_srv_ = nh_.advertiseService("global_localization", &MclNode::cbSimpleReset, this); + + private_nh_.param("global_frame_id", global_frame_id_, std::string("map")); + private_nh_.param("footprint_frame_id", footprint_frame_id_, std::string("base_footprint")); + private_nh_.param("odom_frame_id", odom_frame_id_, std::string("odom")); + private_nh_.param("base_frame_id", base_frame_id_, std::string("base_link")); + + tfb_.reset(new tf2_ros::TransformBroadcaster()); + tf_.reset(new tf2_ros::Buffer()); + tfl_.reset(new tf2_ros::TransformListener(*tf_)); +} + +void MclNode::initPF(void) +{ + std::shared_ptr map = std::move(initMap()); + std::shared_ptr om = std::move(initOdometry()); + + Scan scan; + private_nh_.param("laser_min_range", scan.range_min_, 0.0); + private_nh_.param("laser_max_range", scan.range_max_, 100000000.0); + private_nh_.param("scan_increment", scan.scan_increment_, 1); + + Pose init_pose; + private_nh_.param("initial_pose_x", init_pose.x_, 0.0); + private_nh_.param("initial_pose_y", init_pose.y_, 0.0); + private_nh_.param("initial_pose_a", init_pose.t_, 0.0); + + int num_particles; + private_nh_.param("num_particles", num_particles, 0); + + pf_.reset(new Mcl(init_pose, num_particles, scan, om, map)); +} + +std::shared_ptr MclNode::initOdometry(void) +{ + double ff, fr, rf, rr; + private_nh_.param("odom_fw_dev_per_fw", ff, 0.19); + private_nh_.param("odom_fw_dev_per_rot", fr, 0.0001); + private_nh_.param("odom_rot_dev_per_fw", rf, 0.13); + private_nh_.param("odom_rot_dev_per_rot", rr, 0.2); + return std::shared_ptr(new OdomModel(ff, fr, rf, rr)); +} + +std::shared_ptr MclNode::initMap(void) +{ + double likelihood_range; + private_nh_.param("laser_likelihood_max_dist", likelihood_range, 0.2); + + int num; + private_nh_.param("num_particles", num, 0); + + nav_msgs::GetMap::Request req; + nav_msgs::GetMap::Response resp; + ROS_INFO("Requesting the map..."); + while(!ros::service::call("static_map", req, resp)){ + ROS_WARN("Request for map failed; trying again..."); + ros::Duration d(0.5); + d.sleep(); + } + + return std::shared_ptr(new LikelihoodFieldMap(resp.map, likelihood_range)); +} + +void MclNode::cbScan(const sensor_msgs::LaserScan::ConstPtr &msg) +{ + scan_frame_id_ = msg->header.frame_id; + pf_->setScan(msg); +} + +void MclNode::initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg) +{ + init_request_ = true; + init_x_ = msg->pose.pose.position.x; + init_y_ = msg->pose.pose.position.y; + init_t_ = tf2::getYaw(msg->pose.pose.orientation); +} + +void MclNode::loop(void) +{ + if(init_request_){ + pf_->initialize(init_x_, init_y_, init_t_); + init_request_ = false; + } + else if(simple_reset_request_){ + pf_->simpleReset(); + simple_reset_request_ = false; + } + + double x, y, t; + if(not getOdomPose(x, y, t)){ + ROS_INFO("can't get odometry info"); + return; + } + pf_->motionUpdate(x, y, t); + + double lx, ly, lt; + bool inv; + if(not getLidarPose(lx, ly, lt, inv)){ + ROS_INFO("can't get lidar pose info"); + return; + } + + /* + struct timespec ts_start, ts_end; + clock_gettime(CLOCK_REALTIME, &ts_start); + */ + pf_->sensorUpdate(lx, ly, lt, inv); + /* + clock_gettime(CLOCK_REALTIME, &ts_end); + struct tm tm; + localtime_r( &ts_start.tv_sec, &tm); + printf("START: %02d.%09ld\n", tm.tm_sec, ts_start.tv_nsec); + localtime_r( &ts_end.tv_sec, &tm); + printf("END: %02d.%09ld\n", tm.tm_sec, ts_end.tv_nsec); + */ + + double x_var, y_var, t_var, xy_cov, yt_cov, tx_cov; + pf_->meanPose(x, y, t, x_var, y_var, t_var, xy_cov, yt_cov, tx_cov); + + publishOdomFrame(x, y, t); + publishPose(x, y, t, x_var, y_var, t_var, xy_cov, yt_cov, tx_cov); + publishParticles(); + + std_msgs::Float32 alpha_msg; + alpha_msg.data = static_cast(pf_->alpha_); + alpha_pub_.publish(alpha_msg); +} + +void MclNode::publishPose(double x, double y, double t, + double x_dev, double y_dev, double t_dev, + double xy_cov, double yt_cov, double tx_cov) +{ + geometry_msgs::PoseWithCovarianceStamped p; + p.header.frame_id = global_frame_id_; + p.header.stamp = ros::Time::now(); + p.pose.pose.position.x = x; + p.pose.pose.position.y = y; + + p.pose.covariance[6*0 + 0] = x_dev; + p.pose.covariance[6*1 + 1] = y_dev; + p.pose.covariance[6*2 + 2] = t_dev; + + p.pose.covariance[6*0 + 1] = xy_cov; + p.pose.covariance[6*1 + 0] = xy_cov; + p.pose.covariance[6*0 + 2] = tx_cov; + p.pose.covariance[6*2 + 0] = tx_cov; + p.pose.covariance[6*1 + 2] = yt_cov; + p.pose.covariance[6*2 + 1] = yt_cov; + + tf2::Quaternion q; + q.setRPY(0, 0, t); + tf2::convert(q, p.pose.pose.orientation); + + pose_pub_.publish(p); +} + +void MclNode::publishOdomFrame(double x, double y, double t) +{ + geometry_msgs::PoseStamped odom_to_map; + try{ + tf2::Quaternion q; + q.setRPY(0, 0, t); + tf2::Transform tmp_tf(q, tf2::Vector3(x, y, 0.0)); + + geometry_msgs::PoseStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = footprint_frame_id_; + tmp_tf_stamped.header.stamp = ros::Time(0); + tf2::toMsg(tmp_tf.inverse(), tmp_tf_stamped.pose); + + tf_->transform(tmp_tf_stamped, odom_to_map, odom_frame_id_); + + }catch(tf2::TransformException){ + ROS_DEBUG("Failed to subtract base to odom transform"); + return; + } + tf2::convert(odom_to_map.pose, latest_tf_); + + ros::Time transform_expiration = (ros::Time(ros::Time::now().toSec() + 0.2)); + geometry_msgs::TransformStamped tmp_tf_stamped; + tmp_tf_stamped.header.frame_id = global_frame_id_; + tmp_tf_stamped.header.stamp = transform_expiration; + tmp_tf_stamped.child_frame_id = odom_frame_id_; + tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform); + + tfb_->sendTransform(tmp_tf_stamped); +} + +void MclNode::publishParticles(void) +{ + geometry_msgs::PoseArray cloud_msg; + cloud_msg.header.stamp = ros::Time::now(); + cloud_msg.header.frame_id = global_frame_id_; + cloud_msg.poses.resize(pf_->particles_.size()); + + for(int i=0;iparticles_.size();i++){ + cloud_msg.poses[i].position.x = pf_->particles_[i].p_.x_; + cloud_msg.poses[i].position.y = pf_->particles_[i].p_.y_; + cloud_msg.poses[i].position.z = 0; + + tf2::Quaternion q; + q.setRPY(0, 0, pf_->particles_[i].p_.t_); + tf2::convert(q, cloud_msg.poses[i].orientation); + } + particlecloud_pub_.publish(cloud_msg); +} + +bool MclNode::getOdomPose(double& x, double& y, double& yaw) +{ + geometry_msgs::PoseStamped ident; + ident.header.frame_id = footprint_frame_id_; + ident.header.stamp = ros::Time(0); + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + + geometry_msgs::PoseStamped odom_pose; + try{ + this->tf_->transform(ident, odom_pose, odom_frame_id_); + }catch(tf2::TransformException e){ + ROS_WARN("Failed to compute odom pose, skipping scan (%s)", e.what()); + return false; + } + x = odom_pose.pose.position.x; + y = odom_pose.pose.position.y; + yaw = tf2::getYaw(odom_pose.pose.orientation); + + return true; +} + +bool MclNode::getLidarPose(double& x, double& y, double& yaw, bool& inv) +{ + geometry_msgs::PoseStamped ident; + ident.header.frame_id = scan_frame_id_; + ident.header.stamp = ros::Time(0); + tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); + + geometry_msgs::PoseStamped lidar_pose; + try{ + this->tf_->transform(ident, lidar_pose, base_frame_id_); + }catch(tf2::TransformException e){ + ROS_WARN("Failed to compute lidar pose, skipping scan (%s)", e.what()); + return false; + } + x = lidar_pose.pose.position.x; + y = lidar_pose.pose.position.y; + + double roll, pitch; + tf2::getEulerYPR(lidar_pose.pose.orientation, yaw, pitch, roll); + inv = (fabs(pitch) > M_PI/2 || fabs(roll) > M_PI/2) ? true : false; + + return true; +} + +int MclNode::getOdomFreq(void){ + return odom_freq_; +} + +bool MclNode::cbSimpleReset(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res) +{ + return simple_reset_request_ = true; +} + +} + +int main(int argc, char **argv) +{ + + ros::init(argc, argv, "mcl_node"); + emcl::MclNode node; + + ros::Rate loop_rate(node.getOdomFreq()); + while (ros::ok()){ + node.loop(); + ros::spinOnce(); + loop_rate.sleep(); + } + + ros::spin(); + + return 0; +} + diff --git a/src/emcl2/trash/mcl_node.h b/src/emcl2/trash/mcl_node.h new file mode 100644 index 0000000..82cc988 --- /dev/null +++ b/src/emcl2/trash/mcl_node.h @@ -0,0 +1,80 @@ +//SPDX-FileCopyrightText: 2022 Ryuichi Ueda ryuichiueda@gmail.com +//SPDX-License-Identifier: LGPL-3.0-or-later + +#ifndef INTERFACE_H__ +#define INTERFACE_H__ + +#include +#include "emcl/Mcl.h" + +#include "tf2_ros/transform_broadcaster.h" +#include "tf2_ros/transform_listener.h" +#include "tf2_ros/message_filter.h" +#include "tf2/LinearMath/Transform.h" + +#include "sensor_msgs/LaserScan.h" +#include "geometry_msgs/PoseWithCovarianceStamped.h" +#include "std_srvs/Empty.h" + +namespace emcl2 { + +class MclNode +{ +public: + MclNode(); + ~MclNode(); + + void loop(void); + int getOdomFreq(void); +private: + std::shared_ptr pf_; + ros::NodeHandle nh_; + ros::NodeHandle private_nh_; + + ros::Publisher particlecloud_pub_; + ros::Publisher pose_pub_; + ros::Publisher alpha_pub_; + ros::Subscriber laser_scan_sub_; + ros::Subscriber initial_pose_sub_; + + ros::ServiceServer global_loc_srv_; + + std::string footprint_frame_id_; + std::string global_frame_id_; + std::string odom_frame_id_; + std::string scan_frame_id_; + std::string base_frame_id_; + + std::shared_ptr tfb_; + std::shared_ptr tfl_; + std::shared_ptr tf_; + + tf2::Transform latest_tf_; + + int odom_freq_; + bool init_request_; + bool simple_reset_request_; + double init_x_, init_y_, init_t_; + + void publishPose(double x, double y, double t, + double x_dev, double y_dev, double t_dev, + double xy_cov, double yt_cov, double tx_cov); + void publishOdomFrame(double x, double y, double t); + void publishParticles(void); + void sendTf(void); + bool getOdomPose(double& x, double& y, double& yaw); + bool getLidarPose(double& x, double& y, double& yaw, bool& inv); + + void initCommunication(void); + void initPF(void); + std::shared_ptr initMap(void); + std::shared_ptr initOdometry(void); + + void cbScan(const sensor_msgs::LaserScan::ConstPtr &msg); + bool cbSimpleReset(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res); + void initialPoseReceived(const geometry_msgs::PoseWithCovarianceStampedConstPtr& msg); +}; + +} + +#endif diff --git a/src/linefit_ground_segmentation/.gitignore b/src/linefit_ground_segmentation/.gitignore deleted file mode 100644 index 8b95ceb..0000000 --- a/src/linefit_ground_segmentation/.gitignore +++ /dev/null @@ -1 +0,0 @@ -*.user \ No newline at end of file diff --git a/src/multi_map_manager/CMakeLists.txt b/src/multi_map_manager/CMakeLists.txt new file mode 100644 index 0000000..2fbb164 --- /dev/null +++ b/src/multi_map_manager/CMakeLists.txt @@ -0,0 +1,202 @@ +cmake_minimum_required(VERSION 3.0.2) +project(multi_map_manager) + +## 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) + +## 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 # Or other packages containing 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 multi_map_manager +# CATKIN_DEPENDS other_catkin_pkg +# 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 +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/multi_map_manager.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/multi_map_manager_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# 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 +catkin_install_python(PROGRAMS + scripts/map_changer + 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_multi_map_manager.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/src/multi_map_manager/README.md b/src/multi_map_manager/README.md new file mode 100644 index 0000000..e69de29 --- /dev/null +++ b/src/multi_map_manager/README.md diff --git a/src/multi_map_manager/apps/icon/folder.png b/src/multi_map_manager/apps/icon/folder.png new file mode 100644 index 0000000..397b8cf --- /dev/null +++ b/src/multi_map_manager/apps/icon/folder.png Binary files differ diff --git a/src/multi_map_manager/apps/icon/invisible.png b/src/multi_map_manager/apps/icon/invisible.png new file mode 100644 index 0000000..de968b3 --- /dev/null +++ b/src/multi_map_manager/apps/icon/invisible.png Binary files differ diff --git a/src/multi_map_manager/apps/icon/locked_button.png b/src/multi_map_manager/apps/icon/locked_button.png new file mode 100644 index 0000000..c23e36d --- /dev/null +++ b/src/multi_map_manager/apps/icon/locked_button.png Binary files differ diff --git a/src/multi_map_manager/apps/icon/maps.png b/src/multi_map_manager/apps/icon/maps.png new file mode 100644 index 0000000..aeb9c3e --- /dev/null +++ b/src/multi_map_manager/apps/icon/maps.png Binary files differ diff --git a/src/multi_map_manager/apps/icon/move_button.png b/src/multi_map_manager/apps/icon/move_button.png new file mode 100644 index 0000000..8229622 --- /dev/null +++ b/src/multi_map_manager/apps/icon/move_button.png Binary files differ diff --git a/src/multi_map_manager/apps/icon/rotate_button.png b/src/multi_map_manager/apps/icon/rotate_button.png new file mode 100644 index 0000000..3a3a019 --- /dev/null +++ b/src/multi_map_manager/apps/icon/rotate_button.png Binary files differ diff --git a/src/multi_map_manager/apps/icon/unlocked_button.png b/src/multi_map_manager/apps/icon/unlocked_button.png new file mode 100644 index 0000000..dd62ba5 --- /dev/null +++ b/src/multi_map_manager/apps/icon/unlocked_button.png Binary files differ diff --git a/src/multi_map_manager/apps/icon/visible.png b/src/multi_map_manager/apps/icon/visible.png new file mode 100644 index 0000000..9fa24fc --- /dev/null +++ b/src/multi_map_manager/apps/icon/visible.png Binary files differ diff --git a/src/multi_map_manager/apps/map_merger.py b/src/multi_map_manager/apps/map_merger.py new file mode 100644 index 0000000..dfbc869 --- /dev/null +++ b/src/multi_map_manager/apps/map_merger.py @@ -0,0 +1,11 @@ +import tkinter as tk +from mylib.application import Application + + +if __name__ == "__main__": + root = tk.Tk() + w, h = root.winfo_screenwidth()-10, root.winfo_screenheight()-100 + root.geometry("%dx%d+0+0" % (w, h)) + root.title("Multi Map & Waypoints Merger") + app = Application(root) + app.mainloop() \ No newline at end of file diff --git a/src/multi_map_manager/apps/map_trimmer.py b/src/multi_map_manager/apps/map_trimmer.py new file mode 100644 index 0000000..24b689a --- /dev/null +++ b/src/multi_map_manager/apps/map_trimmer.py @@ -0,0 +1,299 @@ +import tkinter as tk +import tkinter.filedialog +import ruamel.yaml +from pathlib import Path +from mylib.mapdisp import MyMap +from PIL import Image, ImageDraw + + +class Application(tk.Frame): + + def __init__(self, master): + super().__init__(master) + self.theme = {"main": "#444", + "bg1": "#222"} + + #### 画面上部のメニューバーを作成 #### + self.menu_bar = tk.Menu(self) + ## Fileメニューの作成 + self.file_menu = tk.Menu(self.menu_bar, tearoff=tk.OFF, + bg=self.theme["main"], fg="white", activebackground="gray", activeborderwidth=5 + ) + self.menu_bar.add_cascade(label=" File ", menu=self.file_menu) + ## File -> Open + self.file_menu.add_command(label="Open", command=self.menu_open, accelerator="Ctrl+O") + ## File -> Save As + self.file_menu.add_command(label="Save As", command=self.menu_saveas, accelerator="Ctrl+Shift+S") + ## File -> Exit メニュー + self.file_menu.add_separator() # 仕切り + self.file_menu.add_command(label="Exit", command=self.menu_exit, accelerator="Ctrl+Q") + ## Edit メニューの作成 + self.edit_menu = tk.Menu(self.menu_bar, tearoff=tk.OFF, + bg=self.theme["main"], fg="white", activebackground="gray", activeborderwidth=5 + ) + self.menu_bar.add_cascade(label=" Edit ", menu=self.edit_menu) + ## Edit -> Trim + self.edit_menu.add_command(label="Trim", command=self.menu_trim, accelerator="Ctrl+T") + + #### メニューバーを設定 #### + self.master.configure(menu=self.menu_bar) + + #### キーバインド #### + self.bind_all("", self.menu_trim) + self.bind_all("", self.menu_saveas) + self.bind_all("", self.menu_open) + self.bind_all("", self.menu_exit) + + #### マップを表示するキャンバス #### + self.canvas = tk.Canvas(self.master, bg="black", highlightthickness=0) + self.canvas.pack(expand=True, fill=tk.BOTH, padx=5, pady=5) + self.update() + self.canv_w = self.canvas.winfo_width() + self.canv_h = self.canvas.winfo_height() + + #### マウスイベントコールバック #### + self.canvas.bind("", self.left_click_move) + self.canvas.bind("", self.left_click) + self.canvas.bind("", self.left_click_release) + self.canvas.bind("", lambda event, scale=1.1: self.ctrl_click(event, scale)) + self.canvas.bind("", lambda event, scale=0.9: self.ctrl_click(event, scale)) + self.canvas.bind("", self.resize_callback) + + #### 変数 #### + self.mymap = None + self.origin_img = [] + self.trim_range = [] + self.trimming_mode = False + return + + + + """ + ++++++++++ File menu functions ++++++++++ + """ + def menu_open(self, event=None): + filepath = tkinter.filedialog.askopenfilename( + parent=self.master, + title="Select map yaml file", + initialdir=str(Path(".")), + filetypes=[("YAML", ".yaml")] + ) + if not filepath: return + with open(filepath) as file: # .yamlを読み込む + map_yaml = ruamel.yaml.YAML().load(file) + + self.mymap = MyMap(Path(filepath).resolve(), map_yaml) + img_w = self.mymap.original_img_pil.width + img_h = self.mymap.original_img_pil.height + scale = 1 + offset_x = 0 + offset_y = 0 + if (self.canv_w / self.canv_h) > (img_w / img_h): + # canvasの方が横長 画像をcanvasの縦に合わせてリサイズ + scale = (self.canv_h) / img_h + offset_x = (self.canv_w - img_w*scale) / 2 + else: + # canvasの方が縦長 画像をcanvasの横に合わせてリサイズ + scale = (self.canv_w) / img_w + offset_y = (self.canv_h - img_h*scale) / 2 + + self.mymap.scale_at(0, 0, scale) + self.mymap.translate(offset_x, offset_y) + self.canvas.create_image(0, 0, anchor=tk.NW, tags="map", + image=self.mymap.get_draw_image((self.canv_w, self.canv_h)) + ) + self.trim_range = [0, 0, img_w, img_h] # [x1, y1, x2, y2] 画像における左上のxy, 右下のxy + origin = self.mymap.origin + resolution = self.mymap.resolution + self.origin_img = [-origin[0]/resolution, origin[1]/resolution+self.mymap.original_img_pil.height] + self.plot_origin() + self.master.title(str(filepath)) + return + + + def menu_saveas(self, event=None): + new_filepath = tkinter.filedialog.asksaveasfilename( + parent=self.master, + title="Save map YAML and PGM files.", + initialdir=str(self.mymap.yaml_path), + filetypes=[("PGM YAML", ".pgm .yaml")], + ) + if len(new_filepath) == 0: return + # origin + origin = [(self.trim_range[0]-self.origin_img[0])*self.mymap.resolution, + (-self.trim_range[3]+self.origin_img[1])*self.mymap.resolution, + 0.0] + # Write map yaml file + yaml_path = Path(new_filepath).with_suffix(".yaml") + line = "\n" + yaml = ["image: ./" + yaml_path.with_suffix(".pgm").name + line] + yaml.append("resolution: " + str(self.mymap.resolution) + line) + yaml.append("origin: " + str(origin) + line) + yaml.append("negate: " + str(self.mymap.map_yaml["negate"]) + line) + yaml.append("occupied_thresh: " + str(self.mymap.map_yaml["occupied_thresh"]) + line) + yaml.append("free_thresh: " + str(self.mymap.map_yaml["free_thresh"]) + line) + with open(yaml_path.resolve(), 'w') as f: + f.write("".join(yaml)) + # Trim and save map image + trimmed_img = self.mymap.original_img_pil.crop(tuple(self.trim_range)) + trimmed_img.save(str(yaml_path.with_suffix(".pgm"))) + return + + + def menu_exit(self, event=None): + self.master.destroy() + + + + """ + ++++++++++ Edit menu functions ++++++++++ + """ + def menu_trim(self, event=None): + if not self.mymap: return + if self.trimming_mode: + self.canvas.delete("upper", "right", "lower", "left", "ul", "ur", "lr", "ll") + self.trimming_mode = False + self.set_alpha(0) + return + self.trimming_mode = True + self.set_alpha(128) + r = 10 + ul_x, ul_y = self.mymap.transform(self.trim_range[0], self.trim_range[1]) + lr_x, lr_y = self.mymap.transform(self.trim_range[2], self.trim_range[3]) + cxy = [ul_x, ul_y, lr_x, ul_y, lr_x, lr_y, ul_x, lr_y] + # トリミング範囲の上下左右に直線を描画 + for tag, x1, y1, x2, y2 in [("upper",0,1,2,3), ("right",2,3,4,5), ("lower",4,5,6,7), ("left",6,7,0,1)]: + self.canvas.create_line(cxy[x1], cxy[y1], cxy[x2], cxy[y2], tags=tag, fill="#FFF", width=2) + # 四隅にマーカーを描画 + for tag, xidx, yidx in [("ul",0,1), ("ur",2,3), ("lr",4,5), ("ll",6,7)]: + cx, cy = cxy[xidx], cxy[yidx] + self.canvas.create_oval(cx-r, cy-r, cx+r, cy+r, tags=tag, fill="#BBB", outline="#FFF", activefill="#FFF") + self.canvas.tag_bind(tag, "", lambda event, tag=tag: self.move_trim_range(event, tag)) + return + + + def move_trim_range(self, event, tag): + if self.old_click_point is None: + self.old_click_point = [event.x, event.y] + return + delta_x = event.x - self.old_click_point[0] + delta_y = event.y - self.old_click_point[1] + self.old_click_point = [event.x, event.y] + # 四隅の円の移動 + self.canvas.move(tag, delta_x, delta_y) + if tag == "ul": + self.canvas.move("ur", 0, delta_y) + self.canvas.move("ll", delta_x, 0) + elif tag == "ur": + self.canvas.move("ul", 0, delta_y) + self.canvas.move("lr", delta_x, 0) + elif tag == "lr": + self.canvas.move("ll", 0, delta_y) + self.canvas.move("ur", delta_x, 0) + else: # "ll" + self.canvas.move("lr", 0, delta_y) + self.canvas.move("ul", delta_x, 0) + # 左上のマーカーの座標を取得 + ul = self.canvas.bbox("ul") + ul_x = (ul[0] + ul[2]) / 2 + ul_y = (ul[1] + ul[3]) / 2 + # 右下の座標 + lr = self.canvas.bbox("lr") + lr_x = (lr[0] + lr[2]) / 2 + lr_y = (lr[1] + lr[3]) / 2 + # マーカー間の線を移動 + self.canvas.coords("upper", ul_x, ul_y, lr_x, ul_y) + self.canvas.coords("right", lr_x, ul_y, lr_x, lr_y) + self.canvas.coords("lower", lr_x, lr_y, ul_x, lr_y) + self.canvas.coords("left" , ul_x, lr_y, ul_x, ul_y) + # 画像上の位置に変換し、トリミングの範囲を更新 + img_ul_x, img_ul_y = self.mymap.inv_transform(ul_x, ul_y) + img_lr_x, img_lr_y = self.mymap.inv_transform(lr_x, lr_y) + img_ul_x = max(img_ul_x, 0) + img_ul_y = max(img_ul_y, 0) + img_lr_x = min(img_lr_x, self.mymap.original_img_pil.width) + img_lr_y = min(img_lr_y, self.mymap.original_img_pil.height) + self.trim_range = [img_ul_x, img_ul_y, img_lr_x, img_lr_y] + # 画像を更新して描画 + self.set_alpha(128) + return + + + def set_alpha(self, a: int): + im_a = Image.new("L", self.mymap.original_img_pil.size, a) + draw = ImageDraw.Draw(im_a) + draw.rectangle(tuple(self.trim_range), fill=255) + self.mymap.original_img_pil.putalpha(im_a) + self.canvas.itemconfigure("map", image=self.mymap.get_draw_image((self.canv_w, self.canv_h))) + return + + + + """ + ++++++++++ Plot and move point marker representing origin ++++++++++ + """ + def plot_origin(self): + canv_origin = self.mymap.transform(self.origin_img[0], self.origin_img[1]) + r = 5 + x1 = canv_origin[0] - r + y1 = canv_origin[1] - r + x2 = canv_origin[0] + r + 1 + y2 = canv_origin[1] + r + 1 + if self.canvas.find_withtag("origin"): + self.canvas.moveto("origin", x1, y1) + else: + self.canvas.create_oval(x1, y1, x2, y2, tags="origin", fill='cyan', outline='blue') + self.canvas.lift("origin") + return + + + + """ + ++++++++++ Mouse event callback functions ++++++++++ + """ + def left_click_move(self, event): + if (not self.mymap) or (self.trimming_mode) : return + if self.old_click_point is None: + self.old_click_point = [event.x, event.y] + return + delta_x = event.x - self.old_click_point[0] + delta_y = event.y - self.old_click_point[1] + self.old_click_point = [event.x, event.y] + self.mymap.translate(delta_x, delta_y) + self.canvas.itemconfigure("map", image=self.mymap.get_draw_image((self.canv_w, self.canv_h))) + self.canvas.move("origin", delta_x, delta_y) + return + + + def ctrl_click(self, event, scale): + if (not self.mymap) or (self.trimming_mode): return + self.mymap.scale_at(event.x, event.y, scale) + self.canvas.itemconfigure("map", image=self.mymap.get_draw_image((self.canv_w, self.canv_h))) + self.plot_origin() + return + + + def left_click(self, event): + self.old_click_point = [event.x, event.y] + return + + + def left_click_release(self, event): + self.old_click_point = None + return + + + def resize_callback(self, event): + self.canv_w = self.canvas.winfo_width() + self.canv_h = self.canvas.winfo_height() + return + + + + +if __name__ == "__main__": + root = tk.Tk() + w, h = root.winfo_screenwidth()-10, root.winfo_screenheight()-200 + root.geometry("%dx%d+0+0" % (w, h)) + app = Application(root) + app.mainloop() \ No newline at end of file diff --git a/src/multi_map_manager/apps/mylib/__init__.py b/src/multi_map_manager/apps/mylib/__init__.py new file mode 100644 index 0000000..e69de29 --- /dev/null +++ b/src/multi_map_manager/apps/mylib/__init__.py diff --git a/src/multi_map_manager/apps/mylib/__pycache__/__init__.cpython-38.pyc b/src/multi_map_manager/apps/mylib/__pycache__/__init__.cpython-38.pyc new file mode 100644 index 0000000..e8b3d97 --- /dev/null +++ b/src/multi_map_manager/apps/mylib/__pycache__/__init__.cpython-38.pyc Binary files differ diff --git a/src/multi_map_manager/apps/mylib/__pycache__/application.cpython-38.pyc b/src/multi_map_manager/apps/mylib/__pycache__/application.cpython-38.pyc new file mode 100644 index 0000000..365f736 --- /dev/null +++ b/src/multi_map_manager/apps/mylib/__pycache__/application.cpython-38.pyc Binary files differ diff --git a/src/multi_map_manager/apps/mylib/__pycache__/mapdisp.cpython-38.pyc b/src/multi_map_manager/apps/mylib/__pycache__/mapdisp.cpython-38.pyc new file mode 100644 index 0000000..e7cd5a3 --- /dev/null +++ b/src/multi_map_manager/apps/mylib/__pycache__/mapdisp.cpython-38.pyc Binary files differ diff --git a/src/multi_map_manager/apps/mylib/__pycache__/tools.cpython-38.pyc b/src/multi_map_manager/apps/mylib/__pycache__/tools.cpython-38.pyc new file mode 100644 index 0000000..2aa469d --- /dev/null +++ b/src/multi_map_manager/apps/mylib/__pycache__/tools.cpython-38.pyc Binary files differ diff --git a/src/multi_map_manager/apps/mylib/__pycache__/waypointlib.cpython-38.pyc b/src/multi_map_manager/apps/mylib/__pycache__/waypointlib.cpython-38.pyc new file mode 100644 index 0000000..2bd23ac --- /dev/null +++ b/src/multi_map_manager/apps/mylib/__pycache__/waypointlib.cpython-38.pyc Binary files differ diff --git a/src/multi_map_manager/apps/mylib/application.py b/src/multi_map_manager/apps/mylib/application.py new file mode 100644 index 0000000..bc8f460 --- /dev/null +++ b/src/multi_map_manager/apps/mylib/application.py @@ -0,0 +1,195 @@ +import tkinter as tk +import tkinter.filedialog +from pathlib import Path +from .tools import Tools + + + +class Application(tk.Frame): + + def __init__(self, master): + super().__init__(master) + self.theme = {"main": "#444", + "bg1": "#222"} + + #### 画面上部のメニューバーを作成 #### + self.menu_bar = tk.Menu(self) + ## Fileメニューの作成 + self.file_menu = tk.Menu(self.menu_bar, tearoff=tk.OFF, + bg=self.theme["main"], fg="white", activebackground="gray", activeborderwidth=5 + ) + ## Fileメニュー内のOpenメニューを作成 + self.open_menu = tk.Menu(self.file_menu, tearoff=tk.OFF, + bg=self.theme["main"], fg="white", activebackground="gray", activeborderwidth=5, + disabledforeground="black" + ) + self.open_menu.add_command(label="Base map", command=self.menu_open_base) + self.open_menu.add_command(label="Additional map", command=self.menu_open_addtion, state="disabled") + self.open_menu.add_command(label="Multimaps dir", command=self.menu_open_multi) + self.file_menu.add_cascade(label="Open", menu=self.open_menu) + ## Fileメニューその他 + self.file_menu.add_command(label="Export", command=self.menu_export, accelerator="Ctrl+E") + self.file_menu.add_separator() + self.file_menu.add_command(label="Exit", command=self.menu_exit, accelerator="Ctrl+Q") + ## キーボードショートカットを設定 + self.bind_all("", self.menu_export) + self.bind_all("", self.menu_exit) + ## 大元に作成したメニューバーを設定 + self.menu_bar.add_cascade(label=" File ", menu=self.file_menu) # Fileメニューとしてバーに追加 + self.master.configure(menu=self.menu_bar) + + #### 仕切り線で大きさを変更できるウィンドウ #### + paned_window = tk.PanedWindow(self.master, sashwidth=3, bg="gray", relief=tk.RAISED) + paned_window.pack(expand=True, fill=tk.BOTH) + + #### ツールボタン群とレイヤーリストを表示するフレーム #### + self.tools = Tools(paned_window, self.theme, width=300, bg=self.theme["main"]) + paned_window.add(self.tools, minsize=self.tools.min_width, padx=2, pady=2) + ## マップ画像を表示するフレームを追加 + paned_window.add(self.tools.map_disp, minsize=self.tools.map_disp.min_width, padx=2, pady=2) + return + + + """ + ++++++++++ File menu functions ++++++++++ + """ + def menu_open_base(self, event=None): + map_path = self.open_yaml(title="Select base map yaml file") + if not map_path: return + waypoints_path = self.open_yaml(title="Select waypoints file for the map") + if not waypoints_path: return + + suc = self.tools.set_base_map(Path(map_path).resolve(), Path(waypoints_path).resolve()) + if not suc: return + self.open_menu.entryconfigure("Base map", state="disabled") + self.open_menu.entryconfigure("Multimaps dir", state="disabled") + self.open_menu.entryconfigure("Additional map", state="normal") + return + + + def menu_open_addtion(self, event=None): + map_path = self.open_yaml(title="Select additional map yaml file") + if not map_path: return + waypoints_path = self.open_yaml(title="Select waypoints file for the map") + if not waypoints_path: return + self.tools.add_map(Path(map_path).resolve(), Path(waypoints_path).resolve()) + return + + + def menu_open_multi(self, event=None): + dirpath = tkinter.filedialog.askdirectory( + parent=self.master, + title="Select multi maps directory", + initialdir=str(Path(".")) + ) + if not dirpath: return + dirpath = Path(dirpath) + if not (dirpath / Path("map0.yaml")).exists(): return + waypoints_path = self.open_yaml(title="Select waypoints file for the map") + if not waypoints_path: return + suc = self.tools.set_multimaps(dirpath, Path(waypoints_path).resolve()) + if not suc: return + self.open_menu.entryconfigure("Base map", state="disabled") + self.open_menu.entryconfigure("Multimaps dir", state="disabled") + self.open_menu.entryconfigure("Additional map", state="normal") + return + + + def open_yaml(self, title): + filepath = tkinter.filedialog.askopenfilename( + parent=self.master, + title=title, + initialdir=str(Path(".")), + filetypes=[("YAML", ".yaml")] + ) + return filepath + + + def menu_export(self, event=None): + if (len(self.tools.label_list) < 2): return + ## サブウィンドウを作成 + win = tk.Toplevel() + win.geometry("700x200+50+50") + win.minsize(width=500, height=200) + win.attributes('-topmost', True) + win.title("Export") + font = ("Arial", 12) + + ### ファルダパスを参照するダイアログを開く関数(ボタンコールバック) ### + def ref_btn_callback_d(entry: tk.Entry, init_dir): + dirpath = tkinter.filedialog.askdirectory( + parent=win, + title="Directory path to export maps", + initialdir=init_dir + ) + if not dirpath: return + entry.delete(0, tk.END) + entry.insert(tk.END, str(dirpath)) + + ## サブウィンドウにフォルダ入力エントリーを作成 + frame = tk.Frame(win) + frame.pack(expand=False, fill=tk.X, padx=5, pady=10) + label = tk.Label(frame, text="Directory :", anchor=tk.W, font=font) + label.grid(column=0, row=0, padx=3, pady=2, sticky=tk.EW) + ref_btn = tk.Button(frame, image=self.tools.folder_icon) + ref_btn.grid(column=1, row=1, sticky=tk.E, padx=5) + tbox = tk.Entry(frame, font=font) + tbox.grid(column=0, row=1, padx=20, pady=2, sticky=tk.EW) + init_dir = str(Path(".").resolve()) + tbox.insert(tk.END, init_dir) + ref_btn["command"] = lambda entry=tbox, init_dir=init_dir: ref_btn_callback_d(entry, init_dir) + frame.grid_columnconfigure(0, weight=1) + + ## マルチマップyaml、結合したウェイポイント、合成した地図画像と情報yamlを取得 + map_img_list, map_yaml_list = self.tools.get_map_lists() + wp_yaml, _ = self.tools.get_waypoints_yaml() + merged_img_pil, merged_yaml = self.tools.get_merged_map() + + ### それぞれをファイルに書き込む関数(ボタンコールバック) ### + def export_btn_callback(): + # multi maps + dir_path = Path(tbox.get()).resolve() + if not dir_path.exists(): dir_path.mkdir() + for i, img in enumerate(map_img_list): + img_path = dir_path / Path("map{}.pgm".format(i)) + img.save(str(img_path.resolve())) + map_yaml_list[i]["image"] = "./"+str(img_path.name) + str_yaml = "" + line = "\n" + for key, val in map_yaml_list[i].items(): + str_yaml += "{}: {}".format(key, val) + line + with open(str(img_path.with_suffix(".yaml")), 'w') as f: + f.write(str_yaml) + + # merged waypoints + wp_filepath = dir_path / Path("waypoints.yaml") + with open(wp_filepath, 'w') as f: + f.write(wp_yaml) + + # merged map (yaml, pgm) + yaml_path = dir_path / Path("merged_map.yaml") + img_path = yaml_path.with_suffix(".pgm") + merged_yaml["image"] = "./" + str(img_path.name) + str_yaml = "" + line = "\n" + for key, val in merged_yaml.items(): + str_yaml += "{}: {}".format(key, val) + line + with open(str(yaml_path), 'w') as f: + f.write(str_yaml) + merged_img_pil.save(str(img_path)) + win.destroy() + return + + ## エクスポートボタン、キャンセルボタン + export_btn = tk.Button(win, text="Export", font=font) + export_btn["command"] = export_btn_callback + export_btn.pack(side=tk.RIGHT, padx=50, pady=20) + cancel_btn = tk.Button(win, text="Cancel", font=font) + cancel_btn["command"] = win.destroy + cancel_btn.pack(side=tk.LEFT, padx=50, pady=20) + return + + + def menu_exit(self, event=None): + self.master.destroy() + diff --git a/src/multi_map_manager/apps/mylib/mapdisp.py b/src/multi_map_manager/apps/mylib/mapdisp.py new file mode 100644 index 0000000..3d4f03f --- /dev/null +++ b/src/multi_map_manager/apps/mylib/mapdisp.py @@ -0,0 +1,417 @@ +import tkinter as tk +import numpy as np +import math +import ruamel.yaml +from PIL import Image, ImageTk +from pathlib import Path +from .waypointlib import WaypointList, FinishPose + + + +def read_file(path: Path): + with open(path) as file: # .yamlを読み込む + yaml = ruamel.yaml.YAML().load(file) + return yaml + + + +class MyMap(): + + def __init__(self, path: Path, map_yaml): + self.yaml_path = path.resolve() + if map_yaml["image"][0] == "/": + self.img_path = map_yaml["image"] + else: + self.img_path = self.yaml_path.with_name(map_yaml["image"]).resolve() + self.original_img_pil = Image.open(self.img_path).convert("RGBA") + self.pil_img = self.original_img_pil.copy() + self.tk_img = ImageTk.PhotoImage(self.pil_img) + self.origin = map_yaml["origin"] + self.resolution = map_yaml["resolution"] + self.map_yaml = map_yaml + self.mat_affine = np.eye(3) + self.img_origin = [-self.origin[0]/self.resolution, self.original_img_pil.height+self.origin[1]/self.resolution] + return + + + def translate(self, x, y): + self.affine(x, y, 1) + return + + + def scale_at(self, x, y, scale): + self.affine(-x, -y, 1) + self.affine(0, 0, scale) + self.affine(x, y, 1) + return + + + def rotate(self, theta, canv_center=None): + if not canv_center: + cx, cy = self.original_img_pil.width/2, self.original_img_pil.height/2 + canv_center = np.dot(self.mat_affine, [cx, cy, 1]) + self.translate(-canv_center[0], -canv_center[1]) + mat = [[math.cos(theta), -math.sin(theta), 0], + [math.sin(theta), math.cos(theta), 0], + [0, 0, 1]] + self.mat_affine = (np.dot(mat, self.mat_affine)) + self.translate(canv_center[0], canv_center[1]) + return + + + def affine(self, x, y, scale): + x = float(x) + y = float(y) + scale = float(scale) + mat = [[scale,0,x], [0,scale,y], [0,0,1]] + self.mat_affine = np.dot(mat, self.mat_affine) + return + + + def get_draw_image(self, canvas_size): + mat_inv = np.linalg.inv(self.mat_affine) + self.pil_img = self.original_img_pil.transform(canvas_size, + Image.Transform.AFFINE, tuple(mat_inv.flatten()), Image.Resampling.NEAREST, + fillcolor="#0000" + ) + self.tk_img = ImageTk.PhotoImage(image=self.pil_img) + return self.tk_img + + + def get_corners(self): + # 1 2 画像の四隅の座標を左の順番で返す + # 4 3 + w, h = self.original_img_pil.width, self.original_img_pil.height + xy1 = self.mat_affine[:, 2] + xy2 = np.dot(self.mat_affine, [w, 0, 1]) + xy3 = np.dot(self.mat_affine, [w, h, 1]) + xy4 = np.dot(self.mat_affine, [0, h, 1]) + return xy1[0], xy1[1], xy2[0], xy2[1], xy3[0], xy3[1], xy4[0], xy4[1] + + + def set_transparency(self, a): + self.original_img_pil.putalpha(int(a/100*255)) + return + + + def transform(self, img_x, img_y): + mat = [img_x, img_y, 1] + tf_mat = np.dot(self.mat_affine, mat) + return tf_mat[0], tf_mat[1] + + + def inv_transform(self, x, y): + mat = [x, y, 1] + inv_affine = np.linalg.inv(self.mat_affine) + inv = np.dot(inv_affine, mat) + return inv[0], inv[1] + + + def image2real(self, img_x, img_y): + real_x = (img_x - self.img_origin[0]) * self.resolution + real_y = -(img_y - self.img_origin[1]) * self.resolution + real_x = round(real_x, 6) + real_y = round(real_y, 6) + return real_x, real_y + + + def real2image(self, real_x, real_y): + img_x = self.img_origin[0] + real_x / self.resolution + img_y = self.img_origin[1] - real_y / self.resolution + return img_x, img_y + + + def get_rotate_angle(self): + return math.atan2(self.mat_affine[1,0], self.mat_affine[0,0]) + + + + + +class MapDisplay(tk.Frame): + + def __init__(self, master, theme, **kwargs): + super().__init__(master, kwargs) + self.min_width = 400 + + self.canvas = tk.Canvas(self, bg="black", highlightthickness=0) + self.canvas.pack(expand=True, fill=tk.BOTH, padx=5, pady=5) + self.update() + self.canvas.bind("", self.left_click_move) + self.canvas.bind("", self.left_click) + self.canvas.bind("", self.left_click_release) + self.canvas.bind("", lambda event, scale=1.2: self.ctrl_click(event, scale)) + self.canvas.bind("", lambda event, scale=0.8: self.ctrl_click(event, scale)) + self.canvas.bind("", self.resize_callback) + + self.canv_w = self.canvas.winfo_width() + self.canv_h = self.canvas.winfo_height() + self.base_scale = 1 + self.map_dict = {} + self.waypoints_dict = {} + self.theme = theme + self.old_click_point = None + self.rotate_center = None + self.old_map_rot = None + self.selected_map_key = None + self.mode = 0 + self.base_map_key = "" + self.point_rad = 5 + + # mode を識別するための定数 + self.Normal = 0 + self.MoveSelected = 1 + self.RotateSelected = 2 + return + + + + def add_map(self, path: Path, map_yaml, waypoints_yaml, base=False): + key = self.path2key(path) + if key in self.map_dict.keys(): + return False + new_map = MyMap(path, map_yaml) + img_w = new_map.original_img_pil.width + img_h = new_map.original_img_pil.height + scale = 1 + offset_x = 0 + offset_y = 0 + if base: + if (self.canv_w / self.canv_h) > (img_w / img_h): + # canvasの方が横長 画像をcanvasの縦に合わせてリサイズ + scale = self.canv_h / img_h + offset_x = (self.canv_w - img_w*scale) / 2 + else: + # canvasの方が縦長 画像をcanvasの横に合わせてリサイズ + scale = self.canv_w / img_w + offset_y = (self.canv_h - img_h*scale) / 2 + self.base_map_key = key + self.base_scale = scale + else: + scale = self.base_scale + base_map: MyMap = self.map_dict[self.base_map_key] + img_x, img_y = base_map.real2image(new_map.origin[0], new_map.origin[1]) + offset_x, offset_y = base_map.transform(img_x, img_y-img_h) + + new_map.scale_at(0, 0, scale) + new_map.translate(offset_x, offset_y) + self.canvas.create_image(0, 0, anchor=tk.NW, tags=key, + image=new_map.get_draw_image((self.canv_w, self.canv_h)) + ) + self.map_dict[key] = new_map + self.select_map(path) + self.plot_origin() + # waypoints + self.waypoints_dict[key] = WaypointList(waypoints_yaml) + self.waypoints_dict[key+"fp"] = FinishPose(waypoints_yaml) + self.plot_waypoints() + return True + + + def plot_origin(self): + base_map: MyMap = self.map_dict[self.base_map_key] + canv_origin = base_map.transform(base_map.img_origin[0], base_map.img_origin[1]) + r = self.point_rad + x1 = canv_origin[0] - r + y1 = canv_origin[1] - r + x2 = canv_origin[0] + r + 1 + y2 = canv_origin[1] + r + 1 + if self.canvas.find_withtag("origin"): + self.canvas.moveto("origin", x1, y1) + else: + self.canvas.create_oval(x1, y1, x2, y2, tags="origin", fill='cyan', outline='blue') + self.canvas.lift("origin") + return + + + def plot_waypoints(self): + for key, wp_list in self.waypoints_dict.items(): + if key[-2:] == "fp": + finish_pose: FinishPose = self.waypoints_dict[key] + img_x, img_y = self.map_dict[key[:-2]].real2image(finish_pose.x, finish_pose.y) + cx, cy = self.map_dict[key[:-2]].transform(img_x, img_y) + th = finish_pose.yaw - self.map_dict[key[:-2]].get_rotate_angle() + x0 = cx + y0 = cy + x1 = x0 + math.cos(th) * self.point_rad * 3 + y1 = y0 - math.sin(th) * self.point_rad * 3 + if self.waypoints_dict[key].id is not None: + self.canvas.delete(self.waypoints_dict[key].id) # movetoだとX,毎回削除,再描画 + self.waypoints_dict[key].id = self.canvas.create_line(x0, y0, x1, y1, tags=key, + width=5, arrow=tk.LAST, arrowshape=(4,5,3), fill="#AAF" + ) + self.canvas.lift(self.waypoints_dict[key].id, key[:-2]) + continue + + if len(wp_list.get_id_list()) == 0: # 初めて描画する + for n, wp in enumerate(wp_list.get_waypoint()): + id = self.create_waypoint(key, wp, self.map_dict[key]) + self.waypoints_dict[key].set_id(n+1, id) + else: + for id in wp_list.get_id_list(): + wp = wp_list.get_waypoint(id) + img_x, img_y = self.map_dict[key].real2image(float(wp["x"]), float(wp["y"])) + cx, cy = self.map_dict[key].transform(img_x, img_y) + x0, y0 = cx-self.point_rad, cy-self.point_rad + self.canvas.moveto(id, round(x0), round(y0)) + self.canvas.lift(id, key) + return + + + def create_waypoint(self, key, waypoint: dict, mymap: MyMap): + img_x, img_y = mymap.real2image(float(waypoint["x"]), float(waypoint["y"])) + cx, cy = mymap.transform(img_x, img_y) + r = self.point_rad-1 + x0 = round(cx - r) + y0 = round(cy - r) + x1 = round(cx + r + 1) + y1 = round(cy + r + 1) + id = self.canvas.create_oval(x0, y0, x1, y1, fill='#F88', outline='#F88', tags=key+"wp") + return id + + + def set_transparency(self, path: Path, alpha): + key = self.path2key(path) + self.map_dict[key].set_transparency(alpha) + self.canvas.itemconfigure(key, image=self.map_dict[key].get_draw_image((self.canv_w, self.canv_h))) + + + + def select_map(self, path: Path): + self.selected_map_key = self.path2key(path) + polygon = self.map_dict[self.selected_map_key].get_corners() + if self.canvas.find_withtag("selection_frame"): + self.canvas.coords("selection_frame", polygon) + else: + self.canvas.create_polygon(polygon, tags="selection_frame", fill="", outline="#FF0", dash=(5,3), width=5) + self.canvas.lift(self.selected_map_key) + self.canvas.lift("selection_frame") + self.canvas.lift(self.selected_map_key+"wp") + self.canvas.lift(self.selected_map_key+"fp") + self.canvas.lift("origin") + return + + + def set_vision_state(self, path: Path, vision: bool): + key = self.path2key(path) + if vision: + self.canvas.itemconfigure(key, state=tk.NORMAL) + self.canvas.itemconfigure(key+"wp", state=tk.NORMAL) + self.canvas.itemconfigure(key+"fp", state=tk.NORMAL) + else: + self.canvas.itemconfigure(key, state=tk.HIDDEN) + self.canvas.itemconfigure(key+"wp", state=tk.HIDDEN) + self.canvas.itemconfigure(key+"fp", state=tk.HIDDEN) + + + + def path2key(self, path: Path): + return path.with_suffix("").name + + + def get_map(self, path: Path): + key = self.path2key(path) + return self.map_dict[key] + + + def left_click_move(self, event): + if (len(self.map_dict) == 0): return + if self.old_click_point is None: + self.old_click_point = [event.x, event.y] + return + delta_x = event.x - self.old_click_point[0] + delta_y = event.y - self.old_click_point[1] + self.old_click_point = [event.x, event.y] + + if self.mode == self.RotateSelected: + # 選択されているマップを回転する + if self.rotate_center is None: + self.rotate_center = self.old_click_point + r = self.point_rad + x1, y1 = self.rotate_center[0]-r, self.rotate_center[1]-r + x2, y2 = self.rotate_center[0]+r, self.rotate_center[1]+r + self.canvas.create_oval(x1, y1, x2, y2, fill="#FFA", outline="#FF0", tags="rotation_center") + return + key = self.selected_map_key + cx, cy = self.rotate_center + if (abs(event.x-cx) < 20) and (abs(event.y-cy) < 20): return + map_rot = math.atan2((event.y - cy), (event.x - cx)) + if self.old_map_rot is None: + self.old_map_rot = map_rot + return + theta = map_rot - self.old_map_rot + self.map_dict[key].rotate(theta, canv_center=self.rotate_center) + self.canvas.itemconfigure(key, image=self.map_dict[key].get_draw_image((self.canv_w, self.canv_h))) + if self.canvas.find_withtag("rotation_line"): + self.canvas.coords("rotation_line", cx, cy, event.x, event.y) + else: + self.canvas.create_line(cx, cy, event.x, event.y, tags="rotation_line", width=1, fill="#FAA") + polygon = polygon = self.map_dict[key].get_corners() + self.canvas.coords("selection_frame", polygon) + self.canvas.lift("origin") + self.plot_waypoints() + self.old_map_rot = map_rot + return + + elif self.mode == self.MoveSelected: + # 選択されているマップのみ移動する + key = self.selected_map_key + self.map_dict[key].translate(delta_x, delta_y) + self.canvas.itemconfigure(key, image=self.map_dict[key].get_draw_image((self.canv_w, self.canv_h))) + self.canvas.move(key+"wp", delta_x, delta_y) + self.canvas.move(key+"fp", delta_x, delta_y) + + else: + # 全てのマップを移動する + for key in self.map_dict.keys(): + self.map_dict[key].translate(delta_x, delta_y) + self.canvas.itemconfigure(key, image=self.map_dict[key].get_draw_image((self.canv_w, self.canv_h))) + self.canvas.move(key+"wp", delta_x, delta_y) + self.canvas.move(key+"fp", delta_x, delta_y) + self.canvas.move("origin", delta_x, delta_y) + + self.canvas.move("selection_frame", delta_x, delta_y) + self.canvas.lift("origin") + # self.plot_waypoints() + return + + + def ctrl_click(self, event, scale): + if (len(self.map_dict) == 0): return + self.base_scale *= scale + for key in self.map_dict.keys(): + self.map_dict[key].scale_at(event.x, event.y, scale) + self.canvas.itemconfigure(key, image=self.map_dict[key].get_draw_image((self.canv_w, self.canv_h))) + + self.plot_origin() + self.plot_waypoints() + polygon = polygon = self.map_dict[self.selected_map_key].get_corners() + self.canvas.coords("selection_frame", polygon) + self.canvas.lift("selection_frame") + self.canvas.lift("origin") + return + + + def left_click(self, event): + if (self.mode != self.RotateSelected): return + self.old_click_point = [event.x, event.y] + return + + + def left_click_release(self, event): + self.old_click_point = None + self.old_map_rot = None + self.rotate_center = None + if self.canvas.find_withtag("rotation_line"): + self.canvas.delete("rotation_line") + if self.canvas.find_withtag("rotation_center"): + self.canvas.delete("rotation_center") + return + + + def resize_callback(self, event): + self.canv_w = self.canvas.winfo_width() + self.canv_h = self.canvas.winfo_height() + return + + diff --git a/src/multi_map_manager/apps/mylib/tools.py b/src/multi_map_manager/apps/mylib/tools.py new file mode 100644 index 0000000..c1e320a --- /dev/null +++ b/src/multi_map_manager/apps/mylib/tools.py @@ -0,0 +1,472 @@ +import tkinter as tk +import numpy as np +import ruamel.yaml +import math +from tkinter import messagebox +from PIL import Image, ImageTk +from pathlib import Path +from .mapdisp import MapDisplay, MyMap +from .waypointlib import FinishPose, WaypointList, get_waypoint_yaml + + + +def read_file(path: Path): + with open(path) as file: # .yamlを読み込む + yaml = ruamel.yaml.YAML().load(file) + return yaml + + + +class LayerLabel(tk.Label): + + def __init__(self, master, *args, **kwargs): + super().__init__(master, *args, **kwargs) + self.map_path = Path() + self.map_transparency = tk.IntVar() + self.map_transparency.set(100) + self.state = "unlocked" + + + def set_map_path(self, path: Path): + self.map_path = path + + + +class Tools(tk.Frame): + + def __init__(self, master, theme, **kwargs): + super().__init__(master, kwargs) + self.min_width = 200 + width = self.cget("width") + + #### ツールボタン群を配置 #### + self.btn_frame = tk.Frame(self, height=200, width=width, bg=theme["main"]) + self.btn_frame.pack(expand=False, fill=tk.X) + ## move ボタン + icon = Image.open(Path(__file__).parent.parent / Path("icon","move_button.png")) + icon = icon.resize((30, 30)) + self.move_btn_icon = ImageTk.PhotoImage(image=icon) + self.move_btn = tk.Label(self.btn_frame, image=self.move_btn_icon, bg=theme["main"]) + self.move_btn.bind("", lambda event, btn=self.move_btn: self.btn_entry(event, btn)) + self.move_btn.bind("", lambda event, btn=self.move_btn: self.btn_leave(event, btn)) + self.move_btn.bind("", lambda event, btn=self.move_btn, mode="move": self.btn_clicked(event, btn, mode)) + self.move_btn.grid(column=0, row=0) + ## rotate ボタン + icon = Image.open(Path(__file__).parent.parent / Path("icon","rotate_button.png")) + icon = icon.resize((30, 30)) + self.rot_btn_icon = ImageTk.PhotoImage(image=icon) + self.rot_btn = tk.Label(self.btn_frame, image=self.rot_btn_icon, bg=theme["main"]) + self.rot_btn.bind("", lambda event, btn=self.rot_btn: self.btn_entry(event, btn)) + self.rot_btn.bind("", lambda event, btn=self.rot_btn: self.btn_leave(event, btn)) + self.rot_btn.bind("", lambda event, btn=self.rot_btn, mode="rotate": self.btn_clicked(event, btn, mode)) + self.rot_btn.grid(column=1, row=0) + ## lock, unlock ボタン + icon = Image.open(Path(__file__).parent.parent / Path("icon","locked_button.png")) + icon = icon.resize((30,30)) + self.locked_icon = ImageTk.PhotoImage(image=icon) + icon = Image.open(Path(__file__).parent.parent / Path("icon","unlocked_button.png")) + icon = icon.resize((30,30)) + self.unlocked_icon = ImageTk.PhotoImage(image=icon) + self.lock_btn = tk.Label(self.btn_frame, image=self.unlocked_icon, bg=theme["main"]) + self.lock_btn.bind("", lambda event, btn=self.lock_btn: self.btn_entry(event, btn)) + self.lock_btn.bind("", lambda event, btn=self.lock_btn: self.btn_leave(event, btn)) + self.lock_btn.bind("", self.lock_btn_clicked) + self.lock_btn.grid(column=0, row=1) + ## 余白 + space = tk.Frame(self, height=100, bg=theme["main"]) + space.pack(expand=False, fill=tk.X) + + #### マップリストを表示 #### + ## アイコン + icon = Image.open(Path(__file__).parent.parent / Path("icon","maps.png")) + icon = icon.resize((20, 20)) + self.layer_icon = ImageTk.PhotoImage(image=icon) + layer_label = tk.Label(self, bg=theme["bg1"], + text=" Maps", fg="white", font=("Arial",11,"bold"), + image=self.layer_icon, compound=tk.LEFT + ) + layer_label.pack(expand=False, anchor=tk.W, ipadx=3, ipady=2, padx=5) + ## レイヤーリストを表示するフレームを配置 + self.layers_frame = tk.Frame(self, width=width, bg=theme["bg1"]) + self.layers_frame.pack(expand=True, fill=tk.BOTH, padx=5) + ## 透明度調節用のスクロールバーを配置 + self.tra_bar = tk.Scale(self.layers_frame, from_=0, to=100, resolution=1, highlightthickness=0, + label="Transparency", fg="white", font=("Ariel",9,"bold"), bg=theme["bg1"], + activebackground="grey", borderwidth=2, sliderlength=15, sliderrelief=tk.RAISED, + orient=tk.HORIZONTAL, showvalue=True, state=tk.DISABLED, command=self.change_transparency + ) + self.tra_bar.pack(expand=False, fill=tk.X, padx=3, pady=5) + ## アイコンを読み込む + icon = Image.open(Path(__file__).parent.parent / Path("icon","visible.png")) + icon = icon.resize((18, 17)) + self.visible_icon = ImageTk.PhotoImage(image=icon) + icon = Image.open(Path(__file__).parent.parent / Path("icon","invisible.png")) + icon = icon.resize((18, 17)) + self.invisible_icon = ImageTk.PhotoImage(image=icon) + icon = Image.open(Path(__file__).parent.parent / Path("icon","folder.png")) + icon = icon.resize((20, 14)) + self.folder_icon = ImageTk.PhotoImage(image=icon) + + #### マップ画像を表示するフレームを生成 #### + self.map_disp = MapDisplay(self.master, theme, bg=theme["main"]) + + #### 変数 + self.label_list = [] + self.base_map_layer = LayerLabel(self.layers_frame) + self.selected_layer = LayerLabel(self.layers_frame) + self.base_waypoints_path = Path() + self.theme = theme + return + + + + def btn_entry(self, event, btn: tk.Label): + if btn.cget("bg") == "black": return + btn.configure(bg="#333") + + + def btn_leave(self, event, btn: tk.Label): + if btn.cget("bg") == "black": return + btn.configure(bg=self.theme["main"]) + + + def btn_clicked(self, event, btn: tk.Label, mode): + if (len(self.label_list) == 0) or (self.selected_layer == self.base_map_layer): return + if self.selected_layer.state == "locked": return + if btn.cget("bg") == "black": + self.map_disp.mode = self.map_disp.Normal + btn.configure(bg="#333") + return + # 既に他のモードだった場合ボタンの状態を切り替える + if self.map_disp.mode == self.map_disp.MoveSelected: self.move_btn.configure(bg=self.theme["main"]) + elif self.map_disp.mode == self.map_disp.RotateSelected: self.rot_btn.configure(bg=self.theme["main"]) + # MapDisplayにモードを設定 + if mode == "move": self.map_disp.mode = self.map_disp.MoveSelected + elif mode == "rotate": self.map_disp.mode = self.map_disp.RotateSelected + btn.configure(bg="black") + return + + + def lock_btn_clicked(self, event): + if (len(self.label_list) == 0) or (self.selected_layer == self.base_map_layer): return + if self.lock_btn.cget("bg") == "black": + self.lock_btn.configure(image=self.unlocked_icon, bg=self.theme["main"]) + self.selected_layer.state = "unlocked" + else: + self.lock_btn.configure(image=self.locked_icon, bg="black") + self.selected_layer.state = "locked" + return + + + + def set_base_map(self, map_path: Path, wp_path: Path): + map_yaml = read_file(map_path) + if not ("image" in map_yaml): + messagebox.showerror(title="Format error", message="Selected map file is unexpected format.") + return False + wp_yaml = read_file(wp_path) + if (not "waypoints" in wp_yaml) or (not "finish_pose" in wp_yaml): + messagebox.showerror(title="Format error", message="Selected waypoints file is unexpected format.") + return False + try: + self.map_disp.add_map(map_path, map_yaml, wp_yaml, base=True) + except (FileNotFoundError, FileExistsError): + messagebox.showerror(title="Image file is not found", message="\""+map_yaml["image"]+"\" is not found.") + return False + self.append_layer(map_path, base=True) + self.base_map_layer.state = "locked" + self.lock_btn.configure(image=self.locked_icon, bg="black") + self.base_waypoints_path = wp_path + return True + + + def add_map(self, path: Path, wp_path: Path): + map_yaml = read_file(path) + if not ("image" in map_yaml): + messagebox.showerror(title="Format error", message="Selected map file is unexpected format.") + return False + wp_yaml = read_file(wp_path) + if (not "waypoints" in wp_yaml) or (not "finish_pose" in wp_yaml): + messagebox.showerror(title="Format error", message="Selected waypoints file is unexpected format.") + return False + try: + if self.map_disp.add_map(path, map_yaml, wp_yaml): + self.append_layer(path) + else: + i = 2 + path2 = path.with_name(path.with_suffix("").name + "-" + str(i)) + while(not self.map_disp.add_map(path2, map_yaml, wp_yaml)): + i += 1 + path2 = path.with_name(path.with_suffix("").name + "-" + str(i)) + self.append_layer(path2) + path = path2 + except (FileNotFoundError, FileExistsError): + messagebox.showerror(title="Image file is not found", message="\""+map_yaml["image"]+"\" is not found.") + return False + self.selected_layer.map_transparency.set(70) + self.map_disp.set_transparency(path, 70) + self.tra_bar.configure(variable=self.selected_layer.map_transparency) + return True + + + def set_multimaps(self, dirpath: Path, wp_path: Path): + all_wp_yaml = read_file(wp_path) + if (not "waypoints" in all_wp_yaml) or (not "finish_pose" in all_wp_yaml): + messagebox.showerror(title="Format error", message="Selected waypoints file is unexpected format.") + return False + map_idx = 0 + wp_idx = 0 + while(True): + map_path = dirpath / Path("map{}.yaml".format(map_idx)) + if (not map_path.exists()) or (wp_idx >= len(all_wp_yaml["waypoints"])): break + map_yaml = read_file(map_path) + wp_yaml = {"waypoints":[]} + while(True): + if wp_idx >= len(all_wp_yaml["waypoints"]): + wp_yaml["finish_pose"] = all_wp_yaml["finish_pose"] + break + point = all_wp_yaml["waypoints"][wp_idx] + if not "change_map" in point["point"].keys(): + wp_yaml["waypoints"].append(point) + wp_idx += 1 + else: + finish_pose = point["point"] + wp_yaml["finish_pose"] = { + "header":{"seq":0, "stamp":0, "frame_id":"map"}, + "pose":{ + "position":{"x":finish_pose["x"], "y":finish_pose["y"], "z":finish_pose["z"]}, + "orientation":{"x":0, "y":0, "z":0, "w":1} + } + } + break + if map_idx==0: + self.map_disp.add_map(map_path, map_yaml, wp_yaml, base=True) + self.append_layer(map_path, base=True) + self.base_map_layer.state = "locked" + self.lock_btn.configure(image=self.locked_icon, bg="black") + self.base_waypoints_path = wp_path + else: + self.map_disp.add_map(map_path, map_yaml, wp_yaml) + self.append_layer(map_path) + self.selected_layer.map_transparency.set(70) + self.map_disp.set_transparency(map_path, 70) + self.tra_bar.configure(variable=self.selected_layer.map_transparency) + if "change_map" in point["point"].keys(): map_idx = int(point["point"]["change_map"]) + wp_idx += 1 + + return True + + + def append_layer(self, path: Path, base=None): + name = " " + path.with_suffix("").name + font = ("Arial",10) + if base: + name += " ( base )" + font = ("Arial", 10, "bold") + label = LayerLabel(self.layers_frame, bg=self.theme["main"], bd=0, + text=name, fg="white", font=font, anchor=tk.W, padx=10, pady=2, + image=self.visible_icon, compound=tk.LEFT + ) + label.set_map_path(path) + label.bind("", lambda event, label=label: self.layerlabel_clicked(event, label)) + if self.label_list: + label.pack(expand=False, side=tk.TOP, fill=tk.X, padx=2, pady=2, ipady=3, before=self.label_list[-1]) + else: + label.pack(expand=False, side=tk.TOP, fill=tk.X, padx=2, pady=2, ipady=3) + + if self.selected_layer is not None: + self.selected_layer.configure(bg=self.theme["bg1"]) + self.selected_layer = label + self.tra_bar.configure(variable=self.selected_layer.map_transparency, state=tk.NORMAL) + self.lock_btn.configure(image=self.unlocked_icon, bg=self.theme["main"]) + self.label_list.append(label) + if base: self.base_map_layer = label + return + + + def layerlabel_clicked(self, event, label: LayerLabel): + px = label.cget("padx") + imw = self.visible_icon.width() + if (px-3 < event.x) and (event.x < px+imw+3): + # 可視アイコンがクリックされたとき + fg = label.cget("fg") + if fg == "white": + label.configure(image=self.invisible_icon, fg="grey") + self.map_disp.set_vision_state(label.map_path, vision=False) + else: + label.configure(image=self.visible_icon, fg="white") + self.map_disp.set_vision_state(label.map_path, vision=True) + + if label != self.selected_layer: + self.selected_layer.configure(bg=self.theme["bg1"]) + label.configure(bg=self.theme["main"]) + self.selected_layer = label + self.tra_bar.configure(variable=self.selected_layer.map_transparency) + self.map_disp.select_map(self.selected_layer.map_path) + for btn in [self.move_btn, self.rot_btn]: + if btn.cget("bg") == "black": + self.map_disp.mode = self.map_disp.Normal + btn.configure(bg=self.theme["main"]) + break + if self.selected_layer.state == "locked": + self.lock_btn.configure(image=self.locked_icon, bg="black") + else: + self.lock_btn.configure(image=self.unlocked_icon, bg=self.theme["main"]) + return + + + def change_transparency(self, event): + alpha = self.selected_layer.map_transparency.get() + self.map_disp.set_transparency(self.selected_layer.map_path, alpha) + return + + + def get_map_lists(self): + base_map: MyMap = self.map_disp.map_dict[self.map_disp.base_map_key] + base_yaml = base_map.map_yaml + img_list = [base_map.original_img_pil] + yaml_list = [base_yaml] + for label in self.label_list[1:]: + mymap: MyMap = self.map_disp.get_map(label.map_path) + # image + img = mymap.original_img_pil.convert("L") + theta = math.degrees(-mymap.get_rotate_angle()) + img = img.rotate(theta, expand=True, fillcolor=205) + img_list.append(img) + # yaml + yaml = mymap.map_yaml + corners = np.array(mymap.get_corners()) + left = corners[[0,2,4,6]].min() + lower = corners[[1,3,5,7]].max() + img_x, img_y = base_map.inv_transform(left, lower) + real_x, real_y = base_map.image2real(img_x, img_y) + yaml["origin"] = [real_x, real_y, 0.0] + yaml_list.append(yaml) + return img_list, yaml_list + + + def get_waypoints_yaml(self): + # ベースのウェイポイントをコピー + waypoints = WaypointList(self.map_disp.waypoints_dict[self.map_disp.base_map_key].waypoints_yaml) + # ベースのfinish poseをウェイポイントに変換 + finish_pose: FinishPose = self.map_disp.waypoints_dict[self.map_disp.base_map_key + "fp"] + # 個別のウェイポイントをリスト化 + map_idx = 1 + wp_yaml_list = [get_waypoint_yaml(waypoints, finish_pose)] + wpc = waypoints.get_waypoint(num=1).copy() + wpc["x"] = finish_pose.x + wpc["y"] = finish_pose.y + wpc["stop"] = "true" + wpc["change_map"] = map_idx + map_idx += 1 + waypoints.append(wpc) + # 残りのウェイポイントを追加していく + base_map: MyMap = self.map_disp.map_dict[self.map_disp.base_map_key] + name = "waypoints-" + base_map.yaml_path.with_suffix("").name + for label in self.label_list[1:]: + mymap: MyMap = self.map_disp.get_map(label.map_path) + name += "-" + mymap.yaml_path.with_suffix("").name + # 2つ目以降の地図のもともとの原点のキャンバス上の位置を取得 + origin = mymap.transform(mymap.img_origin[0], mymap.img_origin[1]) + # ベースのマップから見た原点の座標を計算 + img_x, img_y = base_map.inv_transform(origin[0], origin[1]) + real_x, real_y = base_map.image2real(img_x, img_y) + # 地図の回転角 + theta = -mymap.get_rotate_angle() + # 2つ目以降の地図に対応するウェイポイントの座標を、ベースの地図の座標系に変換する同次変換行列 + mat = [[math.cos(theta), -math.sin(theta), real_x], + [math.sin(theta), math.cos(theta), real_y], + [0, 0, 1 ]] + wp_list: WaypointList = self.map_disp.waypoints_dict[self.map_disp.path2key(label.map_path)] + wp_list_copy = WaypointList(wp_list.waypoints_yaml) + for i, wp in enumerate(wp_list.get_waypoint()): + tf_xy = np.dot(mat, [wp["x"], wp["y"], 1]) # ベースの座標系に変換 + wpc = wp.copy() + wpc["x"] = round(tf_xy[0], 6) + wpc["y"] = round(tf_xy[1], 6) + waypoints.append(wpc) + wp_list_copy.waypoints[i] = wpc + # 2つ目以降の地図のfinish poseも変換 + finish_pose = FinishPose(wp_list.waypoints_yaml) + tf_xy = np.dot(mat, [finish_pose.x, finish_pose.y, 1]) + finish_pose.x = tf_xy[0] + finish_pose.y = tf_xy[1] + finish_pose.yaw = finish_pose.yaw + theta + wp_yaml_list.append(get_waypoint_yaml(wp_list_copy, finish_pose)) + # 最後以外のfinish poseはウェイポイントとして追加 + if label != self.label_list[-1]: + wpc = waypoints.get_waypoint(num=1).copy() + wpc["x"] = finish_pose.x + wpc["y"] = finish_pose.y + wpc["stop"] = "true" + wpc["change_map"] = map_idx + map_idx += 1 + waypoints.append(wpc) + return get_waypoint_yaml(waypoints, finish_pose), wp_yaml_list + + + def get_merged_map(self): + # 1 2 画像の四隅のキャンバス上の座標を取得 + # 4 3 + base_map: MyMap = self.map_disp.map_dict[self.map_disp.base_map_key] + corners = base_map.get_corners() # x1, y1, x2, y2, x3, y3, x4, y4 + img_corners = np.array(corners) + # ベースの地図画像を基準として画像上の座標に変換 + for i in range(0,8,2): + img_corners[i:i+2] = base_map.inv_transform(corners[i], corners[i+1]) + for label in self.label_list[1:]: + mymap: MyMap = self.map_disp.get_map(label.map_path) + corners = np.array(mymap.get_corners()) + for i in range(0,8,2): + corners[i:i+2] = base_map.inv_transform(corners[i], corners[i+1]) + img_corners = np.vstack((img_corners, corners)) + # 合成する地図画像の中で最も外側にある座標を取得 + left = img_corners[:, [0, 2, 4, 6]].min() + upper = img_corners[:, [1, 3, 5, 7]].min() + right = img_corners[:, [0, 2, 4, 6]].max() + lower = img_corners[:, [1, 3, 5, 7]].max() + # 合成後の画像を準備 + offset = 2 # 結合時の画像サイズの不揃いを解消 + img_size = (int(round(lower-upper)+offset), int(round(right-left)+offset)) #(y, x) + unknown = np.full(img_size, 205, dtype=np.uint8) # 未確定領域 + obstacles = np.full(img_size, 255, dtype=np.uint8) # 障害物が0, それ以外が255 + free_area = np.full(img_size, 0, dtype=np.uint8) # 走行可能領域が255, それ以外が0 + # ベースの画像を合成 + img = np.array(base_map.original_img_pil.convert("L"), dtype=np.uint8) + x, y = int(round(img_corners[0,0]-left)), int(round(img_corners[0,1]-upper)) + h, w = img.shape + obstacles[y:y+h, x:x+w] = obstacles[y:y+h, x:x+w] & np.where(img>100, 255, 0) + free_area[y:y+h, x:x+w] = free_area[y:y+h, x:x+w] | np.where(img<230, 0, 255) + name = "merged-" + base_map.yaml_path.with_suffix("").name + # その他の画像も合成 + for i in range(1, len(self.label_list)): + label = self.label_list[i] + mymap: MyMap = self.map_disp.get_map(label.map_path) + img = mymap.original_img_pil.convert("L") + img = img.rotate(-math.degrees(mymap.get_rotate_angle()), + resample=Image.Resampling.NEAREST, expand=True, fillcolor=205) + img = np.array(img, dtype=np.uint8) + x = int(round(img_corners[i, [0, 2, 4, 6]].min() - left)) + y = int(round(img_corners[i, [1, 3, 5, 7]].min() - upper)) + h, w = img.shape + obstacles[y:y+h, x:x+w] = obstacles[y:y+h, x:x+w] & np.where(img>100, 255, 0) + free_area[y:y+h, x:x+w] = free_area[y:y+h, x:x+w] | np.where(img<230, 0, 255) + name += "-" + Path(label.map_path).with_suffix("").name + # 未確定領域、走行可能領域、障害物を合成し、画像に変換 + merged_img = (unknown | free_area) & obstacles + merged_img = merged_img[:-offset, :-offset] # offset分を削除 + merged_img = Image.fromarray(merged_img, "L") + # 原点から合成後の画像の左下までの距離 + origin = [left-base_map.img_origin[0], -lower+base_map.img_origin[1], 0] + origin[0] = origin[0] * base_map.resolution + origin[1] = origin[1] * base_map.resolution + merged_yaml = { + "image":"./" + base_map.yaml_path.with_name(name+".pgm").name, + "resolution":base_map.resolution, + "origin":origin, + "negate":base_map.map_yaml["negate"], + "occupied_thresh":base_map.map_yaml["occupied_thresh"], + "free_thresh":base_map.map_yaml["free_thresh"] + } + return merged_img, merged_yaml + diff --git a/src/multi_map_manager/apps/mylib/waypointlib.py b/src/multi_map_manager/apps/mylib/waypointlib.py new file mode 100644 index 0000000..5174be1 --- /dev/null +++ b/src/multi_map_manager/apps/mylib/waypointlib.py @@ -0,0 +1,106 @@ +import numpy as np +import quaternion + + +class WaypointList(): + def __init__(self, wp_yaml): + self.waypoints = [] + for point in wp_yaml["waypoints"]: + wp = {} + for key, val in point["point"].items(): + wp[key] = val + self.append(wp) + + self.point_keys = self.waypoints[0].keys() + self.number_dict = {} + self.waypoints_yaml = wp_yaml + return + + + def append(self, waypoint: dict, id=None): + self.waypoints.append(waypoint) + if id: self.set_id(len(self.waypoints), id) + return len(self.waypoints) + + + def insert(self, num, waypoint: dict, id=None): + self.waypoints.insert(num-1, waypoint) + for i, n in self.number_dict.items(): + self.number_dict[i] = n+1 if (n>=num) else n + if id: self.set_id(num, id) + return + + + def get_waypoint(self, id=None, num=None): + if id: return self.waypoints[self.get_num(str(id)) - 1] + if num: return self.waypoints[num-1] + return self.waypoints + + + def get_id_list(self): + return self.number_dict.keys() + + + def set_id(self, num, id): + self.number_dict[str(id)] = num + return + + + def get_num(self, id): + return self.number_dict[str(id)] + + + + +class FinishPose(): + def __init__(self, wp_yaml): + super().__init__() + + self.header = {} + for key, val in wp_yaml["finish_pose"]["header"].items(): + self.header[key] = val + + self.position = {} + for key, val in wp_yaml["finish_pose"]["pose"]["position"].items(): + self.position[key] = val + + self.orientation = {} + for key, val in wp_yaml["finish_pose"]["pose"]["orientation"].items(): + self.orientation[key] = val + + self.x = self.position["x"] + self.y = self.position["y"] + self.yaw = self.get_euler() + self.id = None + return + + + def get_euler(self): + o = self.orientation + q = np.quaternion(o["x"], o["y"], o["z"], o["w"]) + return quaternion.as_euler_angles(q)[1] + + + + +def get_waypoint_yaml(waypoints: WaypointList, finish_pose: FinishPose): + s = ["waypoints:" + "\n"] + for point in waypoints.get_waypoint(): + s.append("- point: {") + for i, (key, val) in enumerate(point.items()): + if (i != 0): s.append(", ") + s.append(key + ": " + str(val).lower()) + s.append("}" + "\n") + + s.append("finish_pose:" + "\n") + seq, stamp, frame = (finish_pose.header["seq"], finish_pose.header["stamp"], finish_pose.header["frame_id"]) + s.append(" header: {" + "seq: {}, stamp: {}, frame_id: {}".format(seq,stamp,frame) + "}" + "\n") + s.append(" pose:" + "\n") + x, y, z = finish_pose.x, finish_pose.y, finish_pose.position["z"] + s.append(" position: {" + "x: {}, y: {}, z: {}".format(x, y, z) + "}" + "\n") + q = quaternion.from_euler_angles([0, 0, finish_pose.yaw]) + s.append(" orientation: {" + "x: {}, y: {}, z: {}, w: {}".format(q.x, q.y, q.z, q.w) + "}") + return "".join(s) + + + \ No newline at end of file diff --git a/src/multi_map_manager/package.xml b/src/multi_map_manager/package.xml new file mode 100644 index 0000000..f1e3636 --- /dev/null +++ b/src/multi_map_manager/package.xml @@ -0,0 +1,52 @@ + + + multi_map_manager + 0.0.0 + The multi_map_manager package + + + + + ubuntu + + + + + + TODO + + + + + + + + + + + + + + + + + rospy + nav_msgs + std_msgs + std_srvs + + rospy + nav_msgs + std_msgs + std_srvs + + + catkin + + + + + + + + diff --git a/src/multi_map_manager/scripts/map_changer b/src/multi_map_manager/scripts/map_changer new file mode 100755 index 0000000..407a136 --- /dev/null +++ b/src/multi_map_manager/scripts/map_changer @@ -0,0 +1,87 @@ +#!/usr/bin/env python3 +import rospy +import ruamel.yaml +from pathlib import Path +from std_msgs.msg import UInt16 +from nav_msgs.srv import LoadMap +from std_srvs.srv import Empty +from std_srvs.srv import Trigger + + + +class MultiMapChanger(): + + def __init__(self): + yaml = ruamel.yaml.YAML() + ## Read multimaps directory + self.multimap_dir = rospy.get_param("map_changer/multi_map_dir") + self.multimap_dir = Path(self.multimap_dir).resolve() + self.current_map_num = 0 + ## Read waypoints file and change point number + self.change_point_num = [] + self.next_map_idx = [] + waypoints_path = rospy.get_param("map_changer/waypoints_file") + with open(waypoints_path) as file: + waypoints_yaml = yaml.load(file) + for i, data in enumerate(waypoints_yaml["waypoints"]): + if ("change_map" in data["point"]): + self.change_point_num.append(i+2) + self.next_map_idx.append(data["point"]["change_map"]) + ## Subscribe current waypoint number + self.waypoint_num = 0 + self.wp_num_sub = rospy.Subscriber("/waypoint_num", UInt16, self.waypoint_num_callback) + ## Service clients + self.change_map = rospy.ServiceProxy("/change_map", LoadMap) + self.amcl_update = rospy.ServiceProxy("/request_nomotion_update", Empty) + self.stop_nav = rospy.ServiceProxy("/stop_wp_nav", Trigger) + self.resume_nav = rospy.ServiceProxy("/resume_nav", Trigger) + return + + + def waypoint_num_callback(self, msg): + if (msg.data == self.waypoint_num): return + try: + idx = self.change_point_num.index(msg.data) + self.current_map_num = self.next_map_idx[idx] + self.change_map_service_call() + except ValueError: + pass + + self.waypoint_num = msg.data + return + + + def change_map_service_call(self): + self.stop_nav() + rospy.sleep(0.5) + self.update_amcl_call() + rospy.wait_for_service("/change_map") + try: + res = self.change_map(str(self.multimap_dir / Path("map{}.yaml".format(self.current_map_num)))) + if res.result == 0: + rospy.loginfo("Successfully changed the map") + self.update_amcl_call() + self.resume_nav() + return True + else: + rospy.logerr("Failed to change the map: result=", res.result) + + except rospy.ServiceException: + rospy.logerr("Change map service call failed") + return False + + + def update_amcl_call(self): + rospy.wait_for_service("/request_nomotion_update") + for i in range(0, 5): + self.amcl_update() + rospy.sleep(0.5) + rospy.loginfo("Update amcl pose 5 times") + + + +if __name__ == '__main__': + rospy.init_node("map_changer") + mmc = MultiMapChanger() + rospy.spin() + diff --git a/src/navigation/.gitignore b/src/navigation/.gitignore deleted file mode 100644 index f9f3d9c..0000000 --- a/src/navigation/.gitignore +++ /dev/null @@ -1,4 +0,0 @@ -*~ -*.project -*.cproject - diff --git a/src/openslam_gmapping/.github/ci_cross_platform_env.yml b/src/openslam_gmapping/.github/ci_cross_platform_env.yml deleted file mode 100644 index 26cffa0..0000000 --- a/src/openslam_gmapping/.github/ci_cross_platform_env.yml +++ /dev/null @@ -1,15 +0,0 @@ -name: test -channels: - - robostack - - conda-forge -dependencies: - - compilers - - ninja - - cmake - - catkin_pkg - - pkg-config - - rosdep - - rosdistro - - ros-distro-mutex 0.1 noetic - - ros-noetic-catkin - - ros-noetic-ros-environment diff --git a/src/openslam_gmapping/.github/workflows/cross_platform_ci.yml b/src/openslam_gmapping/.github/workflows/cross_platform_ci.yml deleted file mode 100644 index 3ea2fd3..0000000 --- a/src/openslam_gmapping/.github/workflows/cross_platform_ci.yml +++ /dev/null @@ -1,101 +0,0 @@ -name: OpenSLAM gmapping cross-platform RoboStack build - -on: - workflow_dispatch: - pull_request: - push: - branches: - - master - - "[kmn]*-devel" - -jobs: - run_openslam_gmapping_compilation: - runs-on: ${{ matrix.os }} - name: ${{ matrix.os }} - strategy: - fail-fast: false - matrix: - os: [ubuntu-latest, macos-latest, windows-latest] - - steps: - - uses: actions/checkout@v2 - - - name: Set up Build Dependencies - uses: mamba-org/provision-with-micromamba@main - with: - environment-file: .github/ci_cross_platform_env.yml - micromamba-version: latest - - - name: Set up OpenSLAM gmapping Dependencies on Unix - if: runner.os == 'Linux' || runner.os == 'macOS' - shell: bash -l -eo pipefail {0} - run: | - micromamba activate test - export PATH=$HOME/micromamba-bin:$PATH - rosdep init - rosdep update - rosdep install --from-paths . --ignore-src -r -y - - - name: Build OpenSLAM gmapping on Unix - if: runner.os == 'Linux' || runner.os == 'macOS' - shell: bash -l -eo pipefail {0} - run: | - export CTEST_OUTPUT_ON_FAILURE=1 - - mkdir build - cd build - - cmake .. -DCMAKE_PREFIX_PATH=$CONDA_PREFIX \ - -DCMAKE_INSTALL_PREFIX=$CONDA_PREFIX \ - -DCMAKE_BUILD_TYPE=Release \ - -DCATKIN_SKIP_TESTING=OFF \ - -G "Ninja" - - ninja - - - name: Set up OpenSLAM gmapping on Windows - if: runner.os == 'Windows' - shell: cmd - run: | - echo "Activate environment, and use rosdep to install dependencies" - call C:\Users\runneradmin\micromamba\condabin\micromamba.bat activate test - - rosdep init - rosdep update - rosdep install --from-paths . --ignore-src -r -y - - - name: Build OpenSLAM gmapping on Windows - if: runner.os == 'Windows' - shell: cmd - run: | - - echo "Remove unnecessary / colliding things from PATH" - set "PATH=%PATH:C:\ProgramData\Chocolatey\bin;=%" - set "PATH=%PATH:C:\Program Files (x86)\sbt\bin;=%" - set "PATH=%PATH:C:\Rust\.cargo\bin;=%" - set "PATH=%PATH:C:\Program Files\Git\usr\bin;=%" - set "PATH=%PATH:C:\Program Files\Git\cmd;=%" - set "PATH=%PATH:C:\Program Files\Git\mingw64\bin;=%" - set "PATH=%PATH:C:\Program Files (x86)\Subversion\bin;=%" - set "PATH=%PATH:C:\Program Files\CMake\bin;=%" - set "PATH=%PATH:C:\Program Files\OpenSSL\bin;=%" - set "PATH=%PATH:C:\Strawberry\c\bin;=%" - set "PATH=%PATH:C:\Strawberry\perl\bin;=%" - set "PATH=%PATH:C:\Strawberry\perl\site\bin;=%" - set "PATH=%PATH:c:\tools\php;=%" - set "PATH=%PATH:ostedtoolcache=%" - - call C:\Users\runneradmin\micromamba\condabin\micromamba.bat activate test - - mkdir build - cd build - SET "CTEST_OUTPUT_ON_FAILURE=1" - - cmake .. -DCMAKE_PREFIX_PATH="%CONDA_PREFIX%\Library" ^ - -DCMAKE_INSTALL_PREFIX="%CONDA_PREFIX%\Library" ^ - -DCMAKE_BUILD_TYPE=Release ^ - -DCATKIN_SKIP_TESTING=OFF ^ - -DBoost_USE_STATIC_LIBS=OFF ^ - -G "Ninja" - - ninja diff --git a/src/slam_gmapping/.gitignore b/src/slam_gmapping/.gitignore deleted file mode 100644 index 23255e5..0000000 --- a/src/slam_gmapping/.gitignore +++ /dev/null @@ -1,11 +0,0 @@ -.cproject -.project -.pydevproject -cmake_install.cmake -build/ -bin/ -lib/ -msg_gen/ -srv_gen/ -*.pyc -*~ diff --git a/src/tsukuba2022/config/elecom_joy.yaml b/src/tsukuba2022/config/elecom_joy.yaml index de1c032..53770a3 100644 --- a/src/tsukuba2022/config/elecom_joy.yaml +++ b/src/tsukuba2022/config/elecom_joy.yaml @@ -1,9 +1,12 @@ axis_linear: 1 scale_linear: 0.4 #0.4 -scale_linear_turbo: 0.8 #0.8 +scale_linear_turbo: 0.7 #0.8 axis_angular: 0 -scale_angular: 0.5 #0.9 +scale_angular: 0.4 #0.5 #0.9 -enable_button: 8 # L1 shoulder button -enable_turbo_button: 9 # R1 shoulder button +enable_button: 9 # R1 shoulder button +enable_turbo_button: 7 # R2 shoulder button + +#enable_button: 8 # L1 shoulder button +#enable_turbo_button: 9 # R1 shoulder button diff --git a/src/tsukuba2022/config/gps_parameters.yaml b/src/tsukuba2022/config/gps_parameters.yaml deleted file mode 100644 index 38970f9..0000000 --- a/src/tsukuba2022/config/gps_parameters.yaml +++ /dev/null @@ -1,37 +0,0 @@ -# maintainer:kbkn/mori -# -# name of the port that connects to gps device -dev_name: /dev/sensors/rtkgps -# directory of the file where waypoints will be saved -output_file: /home/ubuntu/catkin_ws/src/igvc2022/config/gps_waypoints/gps_waypoints.yaml -#output_file: /home/ubuntu/catkin_ws/src/igvc2022/config/gps_waypoints/qualification_waypoints.yaml -# country_id: 0, then Japan -# country_id: 1, then USA -country_id: 0 -# true north is 0 degrees, clockwise angle -azimuth: 180 -# latitude and longitude information given by the organizer at IGVC -# - - latitude(1) -# - longitude(1) -# - - latitude(2) -# - longitude(2) -# ............ -latitude_longitude: - - - 42.66792770 - - -83.21932764 - - - 42.66807663 - - -83.21935915 - - - 42.66812064 - - -83.21936060 - - - 42.66826972 - - -83.21934030 - - -# - - 42.66826972 -# - -83,21934030 -# - - 42.66812064 -# - -83.21936060 -# - - 42.66807663 -# - -83.21935915 -# - - 42.66792770 -# - -83.21932764 diff --git a/src/tsukuba2022/config/gps_waypoints/gps_waypoints.yaml b/src/tsukuba2022/config/gps_waypoints/gps_waypoints.yaml deleted file mode 100644 index 1de4c59..0000000 --- a/src/tsukuba2022/config/gps_waypoints/gps_waypoints.yaml +++ /dev/null @@ -1,17 +0,0 @@ -waypoints: - - point: - x: 23.832395277342513 - y: -39.51859423889264 - z: 0 - - point: - x: 7.288423107180874 - y: -42.101774823056566 - z: 0 - - point: - x: 2.399529025831852 - y: -42.22065671153237 - z: 0 - - point: - x: -14.161232871434652 - y: -40.556537994560074 - z: 0 diff --git a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_north.yaml b/src/tsukuba2022/config/gps_waypoints/gps_waypoints_north.yaml deleted file mode 100644 index ff46ecf..0000000 --- a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_north.yaml +++ /dev/null @@ -1,17 +0,0 @@ -waypoints: - - point: - x: 18.6965 - y: 41.0993 - z: 0 - - point: - x: 4.5435 - y: 41.0993 - z: 0 - - point: - x: -5.1435 - y: 41.0993 - z: 0 - - point: - x: -19.2965 - y: 41.0993 - z: 0 diff --git a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation.yaml b/src/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation.yaml deleted file mode 100644 index 01d3b85..0000000 --- a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation.yaml +++ /dev/null @@ -1,17 +0,0 @@ -waypoints: - - point: - x: 15.799 - y: 30.600 - z: 0 - - point: - x: 4.700 - y: 30.142 - z: 0 - - point: - x: -4.420 - y: 30.514 - z: 0 - - point: - x: -15.912 - y: 30.702 - z: 0 diff --git a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation_reverse.yaml b/src/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation_reverse.yaml deleted file mode 100644 index 9897947..0000000 --- a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_simulation_reverse.yaml +++ /dev/null @@ -1,17 +0,0 @@ -waypoints: - - point: - x: -15.799 - y: -30.600 - z: 0 - - point: - x: -4.700 - y: -30.142 - z: 0 - - point: - x: 4.420 - y: -30.514 - z: 0 - - point: - x: 15.912 - y: -30.702 - z: 0 diff --git a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_south.yaml b/src/tsukuba2022/config/gps_waypoints/gps_waypoints_south.yaml deleted file mode 100644 index f08bc57..0000000 --- a/src/tsukuba2022/config/gps_waypoints/gps_waypoints_south.yaml +++ /dev/null @@ -1,17 +0,0 @@ -waypoints: - - point: - x: 19.2965 - y: -41.0993 - z: 0 - - point: - x: 5.1435 - y: -41.0993 - z: 0 - - point: - x: -4.5435 - y: -41.0993 - z: 0 - - point: - x: -18.6965 - y: -41.0993 - z: 0 diff --git a/src/tsukuba2022/config/gps_waypoints/qualification_waypoints.yaml b/src/tsukuba2022/config/gps_waypoints/qualification_waypoints.yaml deleted file mode 100644 index de097ab..0000000 --- a/src/tsukuba2022/config/gps_waypoints/qualification_waypoints.yaml +++ /dev/null @@ -1,17 +0,0 @@ -waypoints: - - point: - x: 7.058685 - y: 0.5 - z: 0 - - point: - x: 14.117370781974484 - y: 1 - z: 0 - - point: - x: 14.117370781974484 - y: -2.1647149478696024 - z: 0 - - point: - x: -258532440.12709326 - y: 18422863.225660857 - z: 0 diff --git a/src/tsukuba2022/config/igvc_robot_control.yaml b/src/tsukuba2022/config/igvc_robot_control.yaml deleted file mode 100644 index bb3afc4..0000000 --- a/src/tsukuba2022/config/igvc_robot_control.yaml +++ /dev/null @@ -1,43 +0,0 @@ -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 100 - -igvc_robot: - type : "diff_drive_controller/DiffDriveController" - left_wheel : 'right_wheel_hinge' - right_wheel : 'left_wheel_hinge' - publish_rate: 100 - - enable_odom_tf: false - - pose_covariance_diagonal : [0.00001, 0.00001, 1000000000000.0, 1000000000000.0, 1000000000000.0, 0.001] - twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] - - # Wheel separation and radius multipliers - wheel_separation_multiplier: 1.0 # default: 1.0 - wheel_radius_multiplier : 1.0 # default: 1.0 - - # Velocity commands timeout [s], default 0.5 - cmd_vel_timeout: 1.0 - - # Base frame_id - base_frame_id: base_link - - # Velocity and acceleration limits - # Whenever a min_* is unspecified, default to -max_* - linear: - x: - has_velocity_limits : true - max_velocity : 0.8 # m/s - min_velocity : -0.8 # m/s - has_acceleration_limits: true - max_acceleration : 0.8 # m/s^2 - min_acceleration : -0.8 # m/s^2 - angular: - z: - has_velocity_limits : true - max_velocity : 0.4 # rad/s - min_velocity : -0.4 # rad/s - has_acceleration_limits: true - max_acceleration : 0.3 # rad/s^2 - min_acceleration : -0.3 # rad/s^2 diff --git a/src/tsukuba2022/config/igvc_robot_control_sim.yaml b/src/tsukuba2022/config/igvc_robot_control_sim.yaml deleted file mode 100644 index cb6b6b3..0000000 --- a/src/tsukuba2022/config/igvc_robot_control_sim.yaml +++ /dev/null @@ -1,45 +0,0 @@ -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 100 - -igvc_robot: - #type: "icart_mini_controller/ICartMiniController" - type : "diff_drive_controller/DiffDriveController" - left_wheel : 'left_wheel_hinge' - right_wheel : 'right_wheel_hinge' - publish_rate: 100 - - enable_odom_tf: false - - #pose_covariance_diagonal : [0.00001, 0.00001, 1000000000000.0, 1000000000000.0, 1000000000000.0, 0.001] - #twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] - pose_covariance_diagonal : [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] - twist_covariance_diagonal: [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] - - # Wheel separation and radius multipliers - wheel_separation_multiplier: 1.0 # default: 1.0 - wheel_radius_multiplier : 1.0 # default: 1.0 - - # Velocity commands timeout [s], default 0.5 - cmd_vel_timeout: 1.0 - - # Base frame_id - base_frame_id: base_link - - # Velocity and acceleration limits - # Whenever a min_* is unspecified, default to -max_* - linear: - x: - has_velocity_limits : false - #max_velocity : 0.9 # m/s - #min_velocity : -0.9 # m/s - has_acceleration_limits: true - max_acceleration : 1.5 # m/s^2 - min_acceleration : -1.5 # m/s^2 - angular: - z: - has_velocity_limits : false - #max_velocity : 0.5 # rad/s - has_acceleration_limits: false - #max_acceleration : 1.5 # rad/s^2 - diff --git a/src/tsukuba2022/config/initial_pose_tsukuba_L.yaml b/src/tsukuba2022/config/initial_pose_tsukuba_L.yaml new file mode 100644 index 0000000..781b411 --- /dev/null +++ b/src/tsukuba2022/config/initial_pose_tsukuba_L.yaml @@ -0,0 +1,7 @@ +# initial pose config +initial_pose_x: 0.0 +initial_pose_y: 3.97 +initial_pose_a: 0.0 +initial_cov_xx: 0.065 +initial_cov_yy: 0.065 +initial_cov_aa: 0.065 diff --git a/src/tsukuba2022/config/initial_pose_tsukuba_R.yaml b/src/tsukuba2022/config/initial_pose_tsukuba_R.yaml new file mode 100644 index 0000000..7d8e1aa --- /dev/null +++ b/src/tsukuba2022/config/initial_pose_tsukuba_R.yaml @@ -0,0 +1,7 @@ +# initial pose config +initial_pose_x: 0.0 +initial_pose_y: 0.0 +initial_pose_a: 0.0 +initial_cov_xx: 0.065 +initial_cov_yy: 0.065 +initial_cov_aa: 0.065 diff --git a/src/tsukuba2022/config/orange2022_control.yaml b/src/tsukuba2022/config/orange2022_control.yaml deleted file mode 100644 index 60740d6..0000000 --- a/src/tsukuba2022/config/orange2022_control.yaml +++ /dev/null @@ -1,43 +0,0 @@ -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 100 - -diff_drive_controller: - type : "diff_drive_controller/DiffDriveController" - left_wheel : 'left_wheel_hinge' - right_wheel : 'right_wheel_hinge' - publish_rate: 100 - - enable_odom_tf: false - - pose_covariance_diagonal : [0.00001, 0.00001, 1000000000000.0, 1000000000000.0, 1000000000000.0, 0.001] - twist_covariance_diagonal: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] - - # Wheel separation and radius multipliers - wheel_separation_multiplier: 1.0 # default: 1.0 - wheel_radius_multiplier : 1.0 # default: 1.0 - - # Velocity commands timeout [s], default 0.5 - cmd_vel_timeout: 1.0 - - # Base frame_id - base_frame_id: base_link - - # Velocity and acceleration limits - # Whenever a min_* is unspecified, default to -max_* - linear: - x: - has_velocity_limits : true - max_velocity : 0.8 # m/s - min_velocity : -0.8 # m/s - has_acceleration_limits: true - max_acceleration : 0.8 # m/s^2 - min_acceleration : -0.8 # m/s^2 - angular: - z: - has_velocity_limits : true - max_velocity : 0.4 # rad/s - min_velocity : -0.4 # rad/s - has_acceleration_limits: true - max_acceleration : 0.3 # rad/s^2 - min_acceleration : -0.3 # rad/s^2 diff --git a/src/tsukuba2022/config/orange2022_control_sim.yaml b/src/tsukuba2022/config/orange2022_control_sim.yaml deleted file mode 100644 index edc0632..0000000 --- a/src/tsukuba2022/config/orange2022_control_sim.yaml +++ /dev/null @@ -1,41 +0,0 @@ -joint_state_controller: - type: joint_state_controller/JointStateController - publish_rate: 100 - -diff_drive_controller: - type : "diff_drive_controller/DiffDriveController" - left_wheel : 'left_wheel_hinge' - right_wheel : 'right_wheel_hinge' - publish_rate: 100 - - enable_odom_tf: false - - pose_covariance_diagonal : [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] - twist_covariance_diagonal: [0.01, 0.01, 10000.0, 10000.0, 10000.0, 10.0] - - # Wheel separation and radius multipliers - wheel_separation_multiplier: 1.0 # default: 1.0 - wheel_radius_multiplier : 1.0 # default: 1.0 - - # Velocity commands timeout [s], default 0.5 - cmd_vel_timeout: 1.0 - - # Base frame_id - base_frame_id: base_link - - # Velocity and acceleration limits - # Whenever a min_* is unspecified, default to -max_* - linear: - x: - has_velocity_limits : false - #max_velocity : 0.9 # m/s - #min_velocity : -0.9 # m/s - has_acceleration_limits: true - max_acceleration : 1.5 # m/s^2 - min_acceleration : -1.5 # m/s^2 - angular: - z: - has_velocity_limits : false - #max_velocity : 0.5 # rad/s - has_acceleration_limits: false - #max_acceleration : 1.5 # rad/s^2 diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa.yaml new file mode 100644 index 0000000..36b429f --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa.yaml @@ -0,0 +1,42 @@ +waypoints: +- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 1} +- point: {x: 11.652461, y: -0.129326, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 18.50064, y: -0.394513, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 26.176818, y: -0.880348, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.8965, y: -2.35386, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.74376, y: -4.864187, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 50.031271, y: -5.398604, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 53.749972, y: -1.656516, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.386011, y: 7.822806, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.036211, y: 19.482823, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.298734, y: 41.727943, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 52.211059, y: 51.67593, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 49.235726, y: 54.096163, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.641821, y: 54.284997, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 34.675792, y: 54.519292, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 27.002736, y: 54.553319, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 17.764658, y: 54.404576, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 9.777545, y: 54.521176, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 4.894381, y: 53.341228, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: 6.111871, y: 50.909564, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 8.203443, y: 46.825564, z: 0.0, vel: 0.3, rad: 1, stop: false} +- point: {x: 9.780651, y: 43.44464, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 11.737483, y: 38.721254, z: 0.0, vel: 0.3, rad: 1, stop: false} +- point: {x: 13.626837, y: 35.04376, z: 0.0, vel: 0.3, rad: 1, stop: false} +- point: {x: 15.516192, y: 31.163835, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 16.966946, y: 28.39728, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 18.965779, y: 24.446008, z: 0.0, vel: 0.3, rad: 1, stop: false} +- point: {x: 20.795431, y: 20.289953, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 22.735394, y: 16.325682, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 24.462339, y: 11.892483, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 26.65534, y: 6.438096, z: 0.0, vel: 0.3, rad: 1, stop: false} +- point: {x: 29.017033, y: 2.277017, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 28.707936, y: -0.820241, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 20.64444, y: -0.449118, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 9.342051, y: 0.900421, z: 0, vel: 1, rad: 1, stop: false, tandem_end: 1} +finish_pose: + header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} + pose: + position: {x: -0.0241434, y: 1.60681, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9999953885138714, w: 0.0030369311798953413} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1-2.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1-2.yaml new file mode 100644 index 0000000..cda43da --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1-2.yaml @@ -0,0 +1,33 @@ +waypoints: +- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.025331, y: -0.023422, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 18.50064, y: -0.394513, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 26.176818, y: -0.880348, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.8965, y: -2.35386, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.74376, y: -4.864187, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 50.530069, y: -5.066462, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 53.505717, y: -1.933611, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.2674, y: 7.98859, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.0977, y: 20.0885, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.298734, y: 41.727943, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 52.033145, y: 52.371588, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 50, y: 54.5, z: 0, vel: 1, rad: 1, stop: true, change_map: true} +- point: {x: 44.457458, y: 54.265651, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 38.331208, y: 54.17344, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 30.568212, y: 54.0757, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 22.183928, y: 53.966732, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 14.496347, y: 53.725704, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 6.34269, y: 53.623967, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -0.732295, y: 53.479098, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -3.648502, y: 50.77132, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -3.260954, y: 43.319186, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -2.632884, y: 33.104345, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -2.248518, y: 23.345314, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -2.22096, y: 11.492785, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -2.253471, y: 0.890283, z: 0.0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} + pose: + position: {x: 1.084303876129681, y: -1.5445686660287592, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.012634000199744012, w: 0.9999201878344856} diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1.yaml new file mode 100644 index 0000000..3747829 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1.yaml @@ -0,0 +1,19 @@ +waypoints: +- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.025331, y: -0.023422, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 18.50064, y: -0.394513, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 26.176818, y: -0.880348, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.8965, y: -2.35386, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.74376, y: -4.864187, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 50.3905, y: -5.337696, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 53.505717, y: -1.933611, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.2674, y: 7.98859, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.0977, y: 20.0885, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.298734, y: 41.727943, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 52.033145, y: 52.371588, z: 0.0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} + pose: + position: {x: 50, y: 54.5, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9999953885138714, w: 0.0030369311798953413} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1109.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1109.yaml new file mode 100644 index 0000000..989189e --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_1109.yaml @@ -0,0 +1,46 @@ +waypoints: +- point: {x: 7.08627, y: -0.250988, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.6821, y: -0.496924, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 23.7637, y: -0.952438, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 29.0862, y: -1.5478, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 37.9975, y: -3.79624, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 49.740296, y: -5.030009, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.387223, y: -1.962999, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.0937, y: 4.84613, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.1208, y: 15.9712, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.9231, y: 23.9035, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.8191, y: 30.6399, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.4754, y: 37.4937, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.491397, y: 43.642536, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.428564, y: 50.443692, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 49.8563, y: 53.7376, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.150786, y: 54.123517, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.711161, y: 54.310677, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 27.224745, y: 54.404257, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 19.78512, y: 54.357467, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.877594, y: 54.310677, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 5.40638, y: 52.606, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: 6.851567, y: 49.302385, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 8.366118, y: 45.793883, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 9.943652, y: 42.303169, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 12.682168, y: 36.812018, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 14.954459, y: 32.003984, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 16.0829, y: 29.5877, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 17.81952, y: 25.746953, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 19.531971, y: 21.92687, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 21.244422, y: 18.436106, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 22.759282, y: 15.11, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 24.037871, y: 12.029397, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 25.494666, y: 8.970128, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 26.974545, y: 6.61361, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 27.979409, y: 4.678389, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 28.8439, y: 2.58357, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 28.3414, y: 0.479003, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 25.5834, y: -0.68715, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 19.321898, y: -0.694822, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.290472, y: -0.317507, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1667998750.2863405, frame_id: map} + pose: + position: {x: 0.0648544, y: 0.00733662, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.999998523619772, w: 0.0017183591814064413} diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_2.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_2.yaml new file mode 100644 index 0000000..7d432c8 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_2.yaml @@ -0,0 +1,19 @@ +waypoints: +- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.025331, y: -0.023422, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 18.787577, y: -0.169002, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 27.171158, y: -0.322829, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.862517, y: -0.322829, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 43.015357, y: -0.476656, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 50.091407, y: -0.55357, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 53.091037, y: 2.061492, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.93721, y: 9.52211, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.629555, y: 19.751617, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.895084, y: 41.365471, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 53.259834, y: 51.961747, z: 0.0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} + pose: + position: {x: 50, y: 54.5, z: 0} + orientation: {x: 0, y: 0, z: 0.999995, w: 0.00303693} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_inv.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_inv.yaml new file mode 100644 index 0000000..6acc83e --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_inv.yaml @@ -0,0 +1,41 @@ +waypoints: +- point: {x: 8.659451, y: -0.080267, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 20.64444, y: -0.449118, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 28.707936, y: -0.820241, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 29.017033, y: 2.277017, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 26.65534, y: 6.438096, z: 0.0, vel: 0.2, rad: 1, stop: false} +- point: {x: 24.462339, y: 11.892483, z: 0, vel: 0.2, rad: 1, stop: false} +- point: {x: 22.735394, y: 16.325682, z: 0, vel: 0.2, rad: 1, stop: false} +- point: {x: 20.795431, y: 20.289953, z: 0, vel: 0.2, rad: 1, stop: false} +- point: {x: 18.965779, y: 24.446008, z: 0.0, vel: 0.2, rad: 1, stop: false} +- point: {x: 16.966946, y: 28.39728, z: 0, vel: 0.2, rad: 1, stop: false} +- point: {x: 15.516192, y: 31.163835, z: 0, vel: 0.2, rad: 1, stop: false} +- point: {x: 13.626837, y: 35.04376, z: 0.0, vel: 0.2, rad: 1, stop: false} +- point: {x: 11.737483, y: 38.721254, z: 0.0, vel: 0.2, rad: 1, stop: false} +- point: {x: 9.780651, y: 43.44464, z: 0, vel: 0.2, rad: 1, stop: false} +- point: {x: 6.111871, y: 50.909564, z: 0, vel: 0.2, rad: 1, stop: false} +- point: {x: 5.480287, y: 53.484484, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: 8.259034, y: 55.866488, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 17.577555, y: 55.427821, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 27.002736, y: 54.553319, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.675792, y: 54.519292, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.641821, y: 54.284997, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 50.041638, y: 54.187374, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.033145, y: 52.371588, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 52.298734, y: 41.727943, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.0977, y: 20.0885, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.2674, y: 7.98859, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.505717, y: -1.933611, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 50.031271, y: -5.398604, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 42.74376, y: -4.864187, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.8965, y: -2.35386, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 26.176818, y: -0.880348, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 17.894184, y: -0.500027, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.025331, y: -0.023422, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} + pose: + position: {x: 0.0, y: 0.0, z: 0} + orientation: {x: 0, y: 0, z: 1, w: 0} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim.yaml new file mode 100644 index 0000000..33c7c83 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim.yaml @@ -0,0 +1,23 @@ +waypoints: +- point: {x: 3.876438, y: 0.067258, z: 0.00511169, vel: 1, rad: 1, stop: false} +- point: {x: 10.24828, y: 0.067258, z: -0.00192642, vel: 1, rad: 1, stop: false} +- point: {x: 14.343374, y: 0.067258, z: 0.00251579, vel: 1, rad: 1, stop: false} +- point: {x: 15.695671, y: 1.465396, z: 0.0, vel: 1.0, rad: 1.0, stop: false} +- point: {x: 15.731122, y: 6.432358, z: 0.00242996, vel: 1, rad: 1, stop: false} +- point: {x: 15.770729, y: 11.224717, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 15.840833, y: 15.530818, z: 0.0023098, vel: 1, rad: 1, stop: false} +- point: {x: 14.381574, y: 17.020638, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 9.36751, y: 17.0985, z: 0.00177956, vel: 1, rad: 1, stop: false} +- point: {x: 4.640448, y: 17.165799, z: 0.000879288, vel: 1, rad: 1, stop: false} +- point: {x: 3.318711, y: 15.828782, z: 0.0, vel: 1, rad: 1, stop: true} +- point: {x: 4.72936, y: 13.403, z: 0.00301743, vel: 1, rad: 1, stop: false} +- point: {x: 6.72777, y: 10.9204, z: 0.00507927, vel: 1, rad: 1, stop: false} +- point: {x: 8.047505, y: 8.46548, z: 0.00030899, vel: 1, rad: 1, stop: false} +- point: {x: 9.32663, y: 6.47157, z: 0.00183296, vel: 1, rad: 1, stop: false} +- point: {x: 11.210933, y: 3.520583, z: 0.00384521, vel: 1, rad: 1, stop: false} +- point: {x: 10.872753, y: 0.465013, z: 0.00480747, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 113.132, frame_id: map} + pose: + position: {x: 9.27349, y: 0.143879, z: 0} + orientation: {x: 0, y: 0, z: 0.999983, w: 0.00578372} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_1-2.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_1-2.yaml new file mode 100644 index 0000000..36e3c7f --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_1-2.yaml @@ -0,0 +1,25 @@ +waypoints: +- point: {x: 1.91548, y: -0.0550663, z: 0, vel: 1, rad: 1, stop: false, change_map: true} +- point: {x: 9.79794, y: 0.02867, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 13.9369, y: 0.0678324, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.700148, y: 1.386101, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.837027, y: 5.446853, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.882653, y: 9.416352, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.973906, y: 13.477104, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.6479, y: 16.8488, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: 12.649069, y: 16.968348, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 9.385235, y: 16.95799, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 5.662998, y: 16.946178, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 3.134879, y: 16.223039, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 4.868725, y: 13.373368, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 6.50457, y: 11.50272, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 7.484275, y: 9.79152, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 8.585662, y: 7.884585, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 9.694664, y: 5.982185, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.19084, y: 3.638886, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.307752, y: 1.466401, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 85.975, frame_id: map} + pose: + position: {x: 10.569600461613387, y: -0.02156870555503687, z: 0} + orientation: {x: -0.0, y: 0.0, z: -0.9998723389797014, w: 0.01597828974768534} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_1.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_1.yaml new file mode 100644 index 0000000..3141008 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_1.yaml @@ -0,0 +1,13 @@ +waypoints: +- point: {x: 4.91548, y: -0.0550663, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 9.79794, y: 0.02867, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 13.9369, y: 0.0678324, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.700148, y: 1.386101, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.837027, y: 5.446853, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.882653, y: 9.416352, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 15.973906, y: 13.477104, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 59.85, frame_id: map} + pose: + position: {x: 15.6479, y: 16.8488, z: 0} + orientation: {x: 0, y: 0, z: 0.999942, w: 0.010754} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_2.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_2.yaml new file mode 100644 index 0000000..af7e887 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_2.yaml @@ -0,0 +1,17 @@ +waypoints: +- point: {x: 2.583187, y: -0.004932, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 5.847038, y: -0.004932, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 9.569294, y: -0.004932, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 12.099695, y: 0.710181, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 10.3749, y: 3.56534, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 8.745, y: 5.44117, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 7.77073, y: 7.15547, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 6.6754, y: 9.06589, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 5.57244, y: 10.9718, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 4.083708, y: 13.319835, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 3.97369, y: 15.49268, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 85.975, frame_id: map} + pose: + position: {x: 4.71656, y: 16.9783, z: 0} + orientation: {x: 0, y: 0, z: 0.0143918, w: 0.999896} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_tandem.yaml b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_tandem.yaml new file mode 100644 index 0000000..d045698 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/nakaniwa/waypoints_nakaniwa_sim_tandem.yaml @@ -0,0 +1,25 @@ +waypoints: +- point: {x: 4.491795, y: 0.687617, z: 0.00511169, vel: 0.3, rad: 0.5, stop: false, tandem_start: 1} +- point: {x: 6.850828, y: 0.674796, z: 0.0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 9.179548, y: 0.571663, z: 0.0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 11.982831, y: 0.380964, z: -0.00192642, vel: 0.3, rad: 0.5, stop: false, tandem_end: 1} +- point: {x: 14.343374, y: 0.067258, z: 0.00251579, vel: 1, rad: 1, stop: false} +- point: {x: 15.793538, y: 2.133248, z: 0.0, vel: 0.4, rad: 0.5, stop: false} +- point: {x: 15.731122, y: 6.432358, z: 0.00242996, vel: 1, rad: 1, stop: false, tandem_start: 2} +- point: {x: 15.770729, y: 11.224717, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 15.840833, y: 15.530818, z: 0.0023098, vel: 1, rad: 1, stop: false} +- point: {x: 14.381574, y: 17.020638, z: 0.0, vel: 0.4, rad: 1, stop: false, tandem_end: 2} +- point: {x: 9.36751, y: 17.0985, z: 0.00177956, vel: 1, rad: 1, stop: false} +- point: {x: 4.640448, y: 17.165799, z: 0.000879288, vel: 1, rad: 1, stop: false} +- point: {x: 3.099067, y: 16.356373, z: 0.0, vel: 1, rad: 1, stop: true} +- point: {x: 4.72936, y: 13.403, z: 0.00301743, vel: 1, rad: 1, stop: false} +- point: {x: 6.72777, y: 10.9204, z: 0.00507927, vel: 1, rad: 1, stop: false} +- point: {x: 8.047505, y: 8.46548, z: 0.00030899, vel: 1, rad: 1, stop: false} +- point: {x: 9.32663, y: 6.47157, z: 0.00183296, vel: 1, rad: 1, stop: false} +- point: {x: 11.210933, y: 3.520583, z: 0.00384521, vel: 1, rad: 1, stop: false} +- point: {x: 11.044868, y: 0.845988, z: 0.00480747, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 113.132, frame_id: map} + pose: + position: {x: 3.878206, y: 0.178377, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9998780115811825, w: 0.015619281560321212} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_L_old.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_L_old.yaml new file mode 100644 index 0000000..83f1755 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_L_old.yaml @@ -0,0 +1,49 @@ +waypoints: +- point: {x: 5.211877, y: 3.87158, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 18.219589, y: 3.771521, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 33.428608, y: 3.371284, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 46.74171, y: 2.551006, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.9006, y: 1.6036, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 60.305, y: -4.48562, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 65.3182, y: -15.6003, z: 0.0, vel: 1.0, rad: 0.5, stop: false} +- point: {x: 70.8621, y: -15.9114, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 75.3498, y: -15.8108, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 78.170232, y: -15.925524, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 79.972636, y: -16.851907, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 81.760122, y: -18.473545, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 83.827534, y: -19.279364, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 88.102759, y: -19.979617, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: 87.898391, y: -10.591395, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.55817, y: -2.142565, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.078986, y: 2.818376, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 79.982437, y: 2.845343, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 69.5118, y: 0.541712, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 62.208, y: -5.61149, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 58.7626, y: -8.91244, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.7271, y: -10.4897, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 47.8533, y: -10.6475, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 45.7889, y: -11.658, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 42.9629, y: -12.1382, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 34.9496, y: -12.2287, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 34.424937, y: -15.259358, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 33.437802, y: -17.67943, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 31.686434, y: -18.921309, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 26.267135, y: -18.924958, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: 22.563169, y: -18.795965, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 20.2475, y: -18.8274, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 17.633732, y: -18.935307, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 13.621507, y: -18.616877, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 6.8739, y: -18.5676, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 4.66837, y: -25.1465, z: 0.0, vel: 1, rad: 0.6, stop: false} +- point: {x: 0.810068, y: -26.158161, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -4.47588, y: -26.158161, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -11.258451, y: -25.839731, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -17.276789, y: -25.776045, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -24.036949, y: -25.721442, z: 0.0, vel: 1, rad: 0.4, stop: true} +- point: {x: -35.6457, y: -29.3766, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -38.5361, y: -30.6251, z: 0.0, vel: 1, rad: 1.0, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663386810.6123521, frame_id: map} + pose: + position: {x: -43.5257, y: -31.2852, z: 0} + orientation: {x: 0, y: 0, z: 0.999988, w: 0.00484186} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_R.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_R.yaml new file mode 100644 index 0000000..f148508 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_R.yaml @@ -0,0 +1,66 @@ +waypoints: +- point: {x: 4.09724, y: 0.504168, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.659, y: 1.14789, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 20.5776, y: 1.30268, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.2563, y: 1.64634, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 38.1161, y: 1.91456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.2937, y: 1.73542, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.5451, y: 1.66404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 58.0735, y: 0.128874, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 61.313, y: -6.31239, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.9454, y: -14.2518, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.6144, y: -15.4014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.316, y: -15.5441, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.2391, y: -15.3596, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 77.357, y: -15.2531, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 79.101358, y: -15.32212, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.470272, y: -16.227709, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 81.691765, y: -17.449202, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 83.0514, y: -18.1883, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 85.4238, y: -18.5438, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.9159, y: -17.5321, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.2617, y: -15.0813, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.16, y: -10.9362, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.0087, y: -6.39951, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.8094, y: -2.38376, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.683, y: 3.18917, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 84.1737, y: 4.69392, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.0329, y: 4.54753, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.1995, y: 2.24651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.9941, y: -0.0748514, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.1423, y: -4.43719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 59.449401, y: -7.597903, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.4954, y: -9.77409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 51.7554, y: -10.206, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.1474, y: -10.3002, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 46.051, y: -11.3614, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.5089, y: -11.9516, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 37.4443, y: -12.0861, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 35.2285, y: -12.1586, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.8879, y: -14.2313, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.7788, y: -17.3731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.519273, y: -19.091731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.243205, y: -19.061404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 23.785178, y: -19.00075, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 21.2425, y: -18.9706, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.1694, y: -19.0082, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 17.5523, y: -18.9316, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 15.426, y: -18.7627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 12.495, y: -18.5628, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 10.0156, y: -18.6638, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 7.32172, y: -18.6572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 6.06788, y: -21.9222, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 5.40629, y: -26.6174, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 0.550092, y: -27.6913, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -5.94073, y: -28.0941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -10.5427, y: -28.3094, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -16.6638, y: -28.2209, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -23.255, y: -28.019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -34.563433, y: -33.284636, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -43.9865, y: -35.5365, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -49.5035, y: -37.0547, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666489211.5504568, frame_id: map} + pose: + position: {x: -59.2588, y: -38.328, z: 0} + orientation: {x: 0, y: 0, z: -0.999995, w: 0.00302894} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_R_old.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_R_old.yaml new file mode 100644 index 0000000..6ce0d75 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_1_R_old.yaml @@ -0,0 +1,49 @@ +waypoints: +- point: {x: 5.24883, y: 0.299301, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 20.2006, y: 1.69447, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 33.5002, y: 2.08246, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 47.3383, y: 2.15765, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.9006, y: 1.6036, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 60.305, y: -4.48562, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 65.3182, y: -15.6003, z: 0.0, vel: 1.0, rad: 0.5, stop: false} +- point: {x: 70.8621, y: -15.9114, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 75.3498, y: -15.8108, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 78.170232, y: -15.925524, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 79.972636, y: -16.851907, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 81.760122, y: -18.473545, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 83.827534, y: -19.279364, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 88.102759, y: -19.979617, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: 87.898391, y: -10.591395, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.55817, y: -2.142565, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.078986, y: 2.818376, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 79.982437, y: 2.845343, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 69.5118, y: 0.541712, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 62.208, y: -5.61149, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 58.7626, y: -8.91244, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.7271, y: -10.4897, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 47.8533, y: -10.6475, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 45.7889, y: -11.658, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 42.9629, y: -12.1382, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 34.9496, y: -12.2287, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 34.424937, y: -15.259358, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 33.437802, y: -17.67943, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 31.686434, y: -18.921309, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 26.267135, y: -18.924958, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: 22.563169, y: -18.795965, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 20.2475, y: -18.8274, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 17.633732, y: -18.935307, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 13.621507, y: -18.616877, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 6.8739, y: -18.5676, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 4.66837, y: -25.1465, z: 0.0, vel: 1, rad: 0.6, stop: false} +- point: {x: 0.810068, y: -26.158161, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -4.47588, y: -26.158161, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -11.258451, y: -25.839731, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -17.276789, y: -25.776045, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -24.036949, y: -25.721442, z: 0.0, vel: 1, rad: 0.4, stop: true} +- point: {x: -35.6457, y: -29.3766, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -38.5361, y: -30.6251, z: 0.0, vel: 1, rad: 1.0, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663386810.6123521, frame_id: map} + pose: + position: {x: -43.5257, y: -31.2852, z: 0} + orientation: {x: 0, y: 0, z: 0.999988, w: 0.00484186} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_2.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_2.yaml new file mode 100644 index 0000000..c6e6846 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_2.yaml @@ -0,0 +1,52 @@ +waypoints: +- point: {x: 25.8755, y: -0.754454, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 34.6275, y: -2.4586, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 38.7199, y: -2.80717, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 43.5024, y: -3.07042, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.6483, y: -3.56015, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 57.8412, y: -4.27504, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.4202, y: -4.657, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 72.4979, y: -5.18633, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 79.2305, y: -6.12557, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 84.8009, y: -6.3656, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 96.1326, y: -5.3315, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 102.449, y: -5.66648, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 110.774, y: -6.70261, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 115.777, y: -6.9343, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 122.472, y: -7.13072, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 130.1, y: -7.24474, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 137.627, y: -7.46852, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 145.63, y: -7.68487, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 151.553, y: -10.0288, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 158.992, y: -10.2927, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 166.027, y: -10.6959, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 173.288, y: -11.2635, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 179.294, y: -11.8377, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 185.173, y: -9.25373, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 188.271, y: -15.8407, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 188.96, y: -20.1209, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 188.574, y: -25.0721, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 188.142, y: -33.2484, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.684, y: -41.1688, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.52, y: -46.0992, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.224, y: -50.3032, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 186.892, y: -56.5383, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 186.574, y: -59.9935, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 186.416, y: -64.167, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 186.131, y: -71.68, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 185.923, y: -75.403, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 185.881, y: -81.3765, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.493, y: -83.6783, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.478, y: -86.2267, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.489, y: -88.625, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.794, y: -90.6803, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 187.721, y: -92.1342, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 189.082, y: -94.6175, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 203.146, y: -95.4712, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 205.842, y: -92.7138, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 206.793, y: -82.6605, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666494610.986847688, frame_id: map} + pose: + position: {x: 209.525, y: -82.5591, z: 0} + orientation: {x: 0, y: 0, z: -0.00454468, w: 0.99999} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_3.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_3.yaml new file mode 100644 index 0000000..eba0950 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_3.yaml @@ -0,0 +1,87 @@ +waypoints: +- point: {x: 9.77702, y: -9.35124, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 11.0658, y: -15.3721, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 12.2397, y: -21.8151, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 12.841, y: -28.787, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 13.5362, y: -34.6672, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 14.3203, y: -39.4139, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 14.8336, y: -42.912, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.0212, y: -50.3347, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.6069, y: -55.1182, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 17.7161, y: -62.4678, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 18.7441, y: -68.329, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 20.1344, y: -77.0584, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 21.1453, y: -82.7435, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.4133, y: -87.5299, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 20.4862, y: -95.2313, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 21.2146, y: -99.9, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 22.0481, y: -106.871, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 23.0157, y: -113.055, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 24.3563, y: -122.811, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 25.7573, y: -128.975, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 26.3403, y: -132.192, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.631, y: -143.115, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 30.081, y: -151.275, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 30.999, y: -156.742, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.6453, y: -165.493, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.3496, y: -169.194, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.9911, y: -173.797, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 36.1009, y: -183.85, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 37.9232, y: -191.819, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 39.1094, y: -199.932, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 40.4152, y: -207.271, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 41.3608, y: -213.691, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.1209, y: -216.883, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.5918, y: -220.04, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.6284, y: -223.072, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 43.2545, y: -226.003, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 44.2281, y: -230.068, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 45.8753, y: -234.581, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 47.2838, y: -239.107, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 47.2662, y: -243.955, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.0188, y: -248.266, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.8606, y: -253.776, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 50.5381, y: -258.264, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 51.8096, y: -261.134, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 52.6463, y: -265.871, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 52.221, y: -270.229, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.8503, y: -271.519, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 43.8426, y: -272.184, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 39.2682, y: -273.269, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 35.2283, y: -273.832, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 30.6588, y: -274.219, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 26.9984, y: -273.45, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 25.1512, y: -269.419, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 24.1466, y: -264.346, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 24.386, y: -257.993, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 20.2687, y: -252.105, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.0443, y: -245.94, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 17.9814, y: -240.87, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.776, y: -234.487, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 15.7553, y: -227.874, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 14.1257, y: -220.482, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 13.0743, y: -215.375, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 11.755, y: -209.173, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 10.5923, y: -204.519, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 9.87295, y: -198.553, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 9.11476, y: -194.507, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 8.91155, y: -191.779, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 7.20587, y: -185.409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 5.90841, y: -179.699, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 4.12515, y: -172.833, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 3.1091, y: -168.22, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 2.38034, y: -163.933, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 1.38153, y: -159.197, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 0.119742, y: -153.103, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -0.393062, y: -149.66, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -1.18737, y: -145.401, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -1.86761, y: -142.314, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -2.30478, y: -137.676, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -1.78932, y: -134.716, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -4.34085, y: -131.96, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -12.8035, y: -132.725, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666496150.059657956, frame_id: map} + pose: + position: {x: -19.9693, y: -132.988, z: 0} + orientation: {x: 0, y: 0, z: -0.999956, w: 0.00936597} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_4.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_4.yaml new file mode 100644 index 0000000..ede11fe --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_4.yaml @@ -0,0 +1,62 @@ +waypoints: +- point: {x: 7.14972, y: -0.315182, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 10.3538, y: -0.510438, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 15.5411, y: -0.573815, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 18.8931, y: -0.582, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 22.8075, y: -0.435714, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.7923, y: -0.533493, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 35.8201, y: -0.684123, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 40.2679, y: -0.340193, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 45.5056, y: -0.304914, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 50.9425, y: -0.54716, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 54.5277, y: -0.483903, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 58.5744, y: -0.507125, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.8344, y: -0.859115, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.3995, y: -0.828122, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.8457, y: 0.288451, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.721, y: 2.9897, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.1687, y: 7.70261, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.6521, y: 12.0621, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.9683, y: 16.0807, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.8528, y: 20.1514, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.479, y: 23.6696, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.6673, y: 27.993, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.4136, y: 32.6076, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.1523, y: 36.6777, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 68.8278, y: 40.3373, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 68.595, y: 43.5503, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 68.7169, y: 49.7022, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 68.7101, y: 54.4083, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 68.4521, y: 60.4691, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 68.2843, y: 64.5411, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.9655, y: 69.4042, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.7815, y: 74.0209, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.5966, y: 78.9085, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 66.9799, y: 83.9478, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 66.5875, y: 94.5983, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 66.4498, y: 97.9412, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.7457, y: 103.531, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.459, y: 106.51, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.1596, y: 111.812, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.0902, y: 115.071, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.8377, y: 118.623, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.6613, y: 121.972, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.2866, y: 125.367, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.5679, y: 129.76, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.9927, y: 134.744, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.6274, y: 139.304, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.9389, y: 143.907, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.8441, y: 148.163, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.7443, y: 159.546, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.4807, y: 170.914, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.1126, y: 174.395, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 62.4113, y: 183.773, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 62.214, y: 189.498, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 60.3272, y: 194.661, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 60.0819, y: 201.621, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 61.8948, y: 207.946, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666497569.751569181, frame_id: map} + pose: + position: {x: 64.4583, y: 211.689, z: 0} + orientation: {x: 0, y: 0, z: 0.0137001, w: 0.999906} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_5.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_5.yaml new file mode 100644 index 0000000..c0d9e9d --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_5.yaml @@ -0,0 +1,37 @@ +waypoints: +- point: {x: 9.67825, y: 0.140065, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 17.3371, y: 0.964738, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 22.2638, y: 1.19774, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 25.6939, y: 1.36643, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 29.2721, y: 1.63943, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.1001, y: 1.66546, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 37.392, y: 1.57617, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.2553, y: 1.78286, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 46.1511, y: 1.94883, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 50.6625, y: 2.52083, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 54.483, y: 3.18138, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 61.0413, y: 4.44718, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 65.8479, y: 5.15023, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 72.7584, y: 6.25933, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 76.4122, y: 6.60277, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.9786, y: 6.91495, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 84.9715, y: 7.33446, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.3644, y: 7.20248, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 91.8132, y: 7.2966, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 96.4995, y: 7.06355, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 100.587, y: 6.83167, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 105.284, y: 7.29065, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 109.932, y: 6.8314, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 115.424, y: 7.17386, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 120.288, y: 8.25665, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 125.027, y: 8.92041, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 130.261, y: 9.92347, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 134.854, y: 10.9632, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 138.074, y: 11.7053, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 142.746, y: 12.4801, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 149.677, y: 10.0145, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666498137.866959073, frame_id: map} + pose: + position: {x: 151.792, y: 5.67301, z: 0} + orientation: {x: 0, y: 0, z: -0.714715, w: 0.699416} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_6.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_6.yaml new file mode 100644 index 0000000..74bb75e --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_6.yaml @@ -0,0 +1,51 @@ +waypoints: +- point: {x: 12.3608, y: -0.92216, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 15.4534, y: -1.04998, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.4052, y: -1.06136, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 23.5709, y: -0.858102, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.1856, y: -0.485379, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.033, y: -0.147614, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 37.4806, y: 0.418054, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 41.9788, y: 0.893304, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 47.2871, y: 1.46116, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 51.7951, y: 1.95933, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.0978, y: 2.10117, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 72.2475, y: 2.10815, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 77.8338, y: 0.927688, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 83.0616, y: -0.0943923, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.2669, y: -1.07207, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 91.6959, y: -2.45559, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 97.2278, y: -3.94248, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 101.121, y: -5.05808, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 105.941, y: -6.06026, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 111.333, y: -7.54676, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 118.078, y: -8.93664, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 122.978, y: -9.98193, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 126.469, y: -10.275, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 132.043, y: -11.1487, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 135.322, y: -11.4126, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 139.918, y: -11.7221, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 144.738, y: -12.0389, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 149.754, y: -12.0621, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 157.113, y: -12.0096, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 162.104, y: -12.7223, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 165.132, y: -11.3643, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 170.579, y: -10.1581, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 175.503, y: -8.53377, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 179.798, y: -7.26169, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 183.702, y: -5.88755, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 189.276, y: -3.86218, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 192.534, y: -2.38185, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 196.568, y: -0.608021, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 200.949, y: 1.09074, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 206.363, y: 3.15913, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 209.229, y: 5.09364, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 210.481, y: 7.34948, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 212.823, y: 9.60237, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 215.445, y: 8.90903, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 216.261, y: 7.00336, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666498996.671352770, frame_id: map} + pose: + position: {x: 216.61, y: 6.4212, z: 0} + orientation: {x: 0, y: 0, z: -0.6611, w: 0.750298} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_7.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_7.yaml new file mode 100644 index 0000000..994f8f4 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_7.yaml @@ -0,0 +1,75 @@ +waypoints: +- point: {x: 5.3636, y: 0.0904167, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 11.5044, y: 0.465055, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.699, y: 1.24866, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 23.9469, y: 1.59342, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 27.3978, y: 1.22125, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.4584, y: -0.0330052, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 36.0657, y: -0.64817, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 39.5796, y: -0.823233, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.4722, y: -1.34653, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 45.0522, y: -1.65752, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.1285, y: -1.83046, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 53.9909, y: -2.0272, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 57.7505, y: -1.83758, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 60.1686, y: -1.97482, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.4809, y: -2.7043, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.0506, y: -3.58838, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.8787, y: -4.38322, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.9754, y: -6.00409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 78.2539, y: -6.97766, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 85.92, y: -8.20992, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 91.0165, y: -9.25405, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 95.6054, y: -9.6805, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 99.7147, y: -9.56832, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 103.149, y: -9.34752, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 106.116, y: -7.88057, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 109.569, y: -6.06586, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 112.919, y: -3.91319, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 116.502, y: -2.12353, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 119.759, y: 0.0310771, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 123.029, y: 2.09065, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 127.212, y: 4.48471, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 130.763, y: 6.50064, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 134.614, y: 8.44767, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 137.107, y: 9.20638, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 140.624, y: 10.5317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 143.961, y: 10.5781, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 147.346, y: 9.77895, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 150.397, y: 8.73421, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 154.66, y: 7.48929, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 158.342, y: 6.02823, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 162.934, y: 4.55966, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 166.195, y: 3.45894, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 169.993, y: 2.04407, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 173.566, y: 0.878988, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 177.541, y: -0.293789, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 182.438, y: -1.74787, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 185.46, y: -2.76484, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 188.404, y: -3.36537, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 194.471, y: -4.88014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 199.113, y: -5.33859, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 202.886, y: -5.88745, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 206.441, y: -7.31497, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 208.486, y: -10.3279, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 209.529, y: -14.663, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 210.145, y: -18.5102, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 210.708, y: -21.7332, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 210.066, y: -26.0123, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 208.603, y: -31.8163, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 208.456, y: -36.4555, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 207.626, y: -43.7698, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 206.67, y: -49.5498, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 205.592, y: -54.7511, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 204.77, y: -59.0512, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 206.924, y: -64.381, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 208.642, y: -68.1098, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 210.39, y: -72.1318, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 212.264, y: -75.1983, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 216.875, y: -77.5158, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 225.351, y: -80.4098, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500443.482085479, frame_id: map} + pose: + position: {x: 227.771, y: -78.1322, z: 0} + orientation: {x: 0, y: 0, z: 0.560178, w: 0.828372} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_8.yaml b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_8.yaml new file mode 100644 index 0000000..e1c9832 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/raw/waypoints_tsukuba_8.yaml @@ -0,0 +1,34 @@ +waypoints: +- point: {x: 9.46913, y: 0.529765, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 14.9492, y: 0.871575, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.6856, y: 0.632644, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 24.9351, y: 0.233624, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.0122, y: -0.0124286, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.0594, y: -0.17328, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 35.7966, y: -0.423632, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 39.5993, y: -0.453472, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 43.7265, y: -1.00715, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 46.9868, y: -1.03966, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 50.4449, y: -1.17954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 54.2481, y: -1.22557, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 57.7555, y: -1.21769, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 62.8625, y: -1.11575, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 66.7316, y: -1.22341, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 71.0413, y: -1.23109, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 75.7319, y: -1.16161, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 79.8398, y: -1.10049, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 83.0448, y: -1.1651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.495, y: -0.986142, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 92.5278, y: -1.03608, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 96.6576, y: -0.955216, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 103.025, y: -0.811471, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 109.671, y: -1.51092, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 113.289, y: -2.87296, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 117.055, y: -6.03892, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 121.485, y: -8.93011, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 127.634, y: -9.38217, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500880.699932195, frame_id: map} + pose: + position: {x: 127.665, y: -9.34744, z: 0} + orientation: {x: 0, y: 0, z: -0.0112674, w: 0.999937} diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_L_old.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_L_old.yaml new file mode 100644 index 0000000..83f1755 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_L_old.yaml @@ -0,0 +1,49 @@ +waypoints: +- point: {x: 5.211877, y: 3.87158, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 18.219589, y: 3.771521, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 33.428608, y: 3.371284, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 46.74171, y: 2.551006, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.9006, y: 1.6036, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 60.305, y: -4.48562, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 65.3182, y: -15.6003, z: 0.0, vel: 1.0, rad: 0.5, stop: false} +- point: {x: 70.8621, y: -15.9114, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 75.3498, y: -15.8108, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 78.170232, y: -15.925524, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 79.972636, y: -16.851907, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 81.760122, y: -18.473545, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 83.827534, y: -19.279364, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 88.102759, y: -19.979617, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: 87.898391, y: -10.591395, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.55817, y: -2.142565, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.078986, y: 2.818376, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 79.982437, y: 2.845343, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 69.5118, y: 0.541712, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 62.208, y: -5.61149, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 58.7626, y: -8.91244, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.7271, y: -10.4897, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 47.8533, y: -10.6475, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 45.7889, y: -11.658, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 42.9629, y: -12.1382, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 34.9496, y: -12.2287, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 34.424937, y: -15.259358, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 33.437802, y: -17.67943, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 31.686434, y: -18.921309, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 26.267135, y: -18.924958, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: 22.563169, y: -18.795965, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 20.2475, y: -18.8274, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 17.633732, y: -18.935307, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 13.621507, y: -18.616877, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 6.8739, y: -18.5676, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 4.66837, y: -25.1465, z: 0.0, vel: 1, rad: 0.6, stop: false} +- point: {x: 0.810068, y: -26.158161, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -4.47588, y: -26.158161, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -11.258451, y: -25.839731, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -17.276789, y: -25.776045, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -24.036949, y: -25.721442, z: 0.0, vel: 1, rad: 0.4, stop: true} +- point: {x: -35.6457, y: -29.3766, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -38.5361, y: -30.6251, z: 0.0, vel: 1, rad: 1.0, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663386810.6123521, frame_id: map} + pose: + position: {x: -43.5257, y: -31.2852, z: 0} + orientation: {x: 0, y: 0, z: 0.999988, w: 0.00484186} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_R.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_R.yaml new file mode 100644 index 0000000..f148508 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_R.yaml @@ -0,0 +1,66 @@ +waypoints: +- point: {x: 4.09724, y: 0.504168, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.659, y: 1.14789, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 20.5776, y: 1.30268, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.2563, y: 1.64634, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 38.1161, y: 1.91456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.2937, y: 1.73542, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.5451, y: 1.66404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 58.0735, y: 0.128874, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 61.313, y: -6.31239, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.9454, y: -14.2518, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.6144, y: -15.4014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.316, y: -15.5441, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.2391, y: -15.3596, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 77.357, y: -15.2531, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 79.101358, y: -15.32212, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.470272, y: -16.227709, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 81.691765, y: -17.449202, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 83.0514, y: -18.1883, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 85.4238, y: -18.5438, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.9159, y: -17.5321, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.2617, y: -15.0813, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.16, y: -10.9362, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.0087, y: -6.39951, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.8094, y: -2.38376, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.683, y: 3.18917, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 84.1737, y: 4.69392, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.0329, y: 4.54753, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.1995, y: 2.24651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.9941, y: -0.0748514, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.1423, y: -4.43719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 59.449401, y: -7.597903, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.4954, y: -9.77409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 51.7554, y: -10.206, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.1474, y: -10.3002, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 46.051, y: -11.3614, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.5089, y: -11.9516, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 37.4443, y: -12.0861, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 35.2285, y: -12.1586, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.8879, y: -14.2313, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.7788, y: -17.3731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.519273, y: -19.091731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.243205, y: -19.061404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 23.785178, y: -19.00075, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 21.2425, y: -18.9706, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.1694, y: -19.0082, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 17.5523, y: -18.9316, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 15.426, y: -18.7627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 12.495, y: -18.5628, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 10.0156, y: -18.6638, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 7.32172, y: -18.6572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 6.06788, y: -21.9222, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 5.40629, y: -26.6174, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 0.550092, y: -27.6913, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -5.94073, y: -28.0941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -10.5427, y: -28.3094, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -16.6638, y: -28.2209, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -23.255, y: -28.019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -34.563433, y: -33.284636, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -43.9865, y: -35.5365, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -49.5035, y: -37.0547, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666489211.5504568, frame_id: map} + pose: + position: {x: -59.2588, y: -38.328, z: 0} + orientation: {x: 0, y: 0, z: -0.999995, w: 0.00302894} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_R_old.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_R_old.yaml new file mode 100644 index 0000000..6ce0d75 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_1_R_old.yaml @@ -0,0 +1,49 @@ +waypoints: +- point: {x: 5.24883, y: 0.299301, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 20.2006, y: 1.69447, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 33.5002, y: 2.08246, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 47.3383, y: 2.15765, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.9006, y: 1.6036, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 60.305, y: -4.48562, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 65.3182, y: -15.6003, z: 0.0, vel: 1.0, rad: 0.5, stop: false} +- point: {x: 70.8621, y: -15.9114, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 75.3498, y: -15.8108, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 78.170232, y: -15.925524, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 79.972636, y: -16.851907, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 81.760122, y: -18.473545, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 83.827534, y: -19.279364, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 88.102759, y: -19.979617, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: 87.898391, y: -10.591395, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.55817, y: -2.142565, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 87.078986, y: 2.818376, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 79.982437, y: 2.845343, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 69.5118, y: 0.541712, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 62.208, y: -5.61149, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 58.7626, y: -8.91244, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 55.7271, y: -10.4897, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: 47.8533, y: -10.6475, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 45.7889, y: -11.658, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 42.9629, y: -12.1382, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 34.9496, y: -12.2287, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 34.424937, y: -15.259358, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 33.437802, y: -17.67943, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 31.686434, y: -18.921309, z: 0.0, vel: 0.6, rad: 0.5, stop: false} +- point: {x: 26.267135, y: -18.924958, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: 22.563169, y: -18.795965, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 20.2475, y: -18.8274, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 17.633732, y: -18.935307, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 13.621507, y: -18.616877, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 6.8739, y: -18.5676, z: 0.0, vel: 1, rad: 0.5, stop: false} +- point: {x: 4.66837, y: -25.1465, z: 0.0, vel: 1, rad: 0.6, stop: false} +- point: {x: 0.810068, y: -26.158161, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -4.47588, y: -26.158161, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -11.258451, y: -25.839731, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -17.276789, y: -25.776045, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -24.036949, y: -25.721442, z: 0.0, vel: 1, rad: 0.4, stop: true} +- point: {x: -35.6457, y: -29.3766, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -38.5361, y: -30.6251, z: 0.0, vel: 1, rad: 1.0, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663386810.6123521, frame_id: map} + pose: + position: {x: -43.5257, y: -31.2852, z: 0} + orientation: {x: 0, y: 0, z: 0.999988, w: 0.00484186} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_2.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_2.yaml new file mode 100644 index 0000000..6ca2dad --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_2.yaml @@ -0,0 +1,54 @@ +waypoints: +- point: {x: -65.997293, y: -37.687546, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -74.861316, y: -36.722816, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -78.968532, y: -36.718417, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -83.75627, y: -36.856869, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -88.925109, y: -36.80009, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -98.145582, y: -36.858084, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -105.729932, y: -37.112591, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -112.827094, y: -37.178238, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -119.614722, y: -36.806496, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -125.185643, y: -37.034113, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -136.390826, y: -39.014177, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: -143.746931, y: -39.051802, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -151.30381, y: -38.555669, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -156.31217, y: -38.560155, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -163.008984, y: -38.679659, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -170.633876, y: -38.925466, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -178.163055, y: -39.056873, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -186.167354, y: -39.218148, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -192.881547, y: -39.462594, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -200.031648, y: -39.834995, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -207.181748, y: -40.058435, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -213.661526, y: -40.132915, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -220.588186, y: -40.207396, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -226.546603, y: -39.313633, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.63807, y: -33.11418, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.035577, y: -28.839193, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.883482, y: -23.875298, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.988601, y: -15.877496, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.178122, y: -8.422993, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.051775, y: -2.990049, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.178122, y: 1.27418, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.241296, y: 7.591556, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.462404, y: 12.392761, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.683512, y: 18.141574, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.841447, y: 23.321822, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.999381, y: 28.028267, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -231.094142, y: 32.45043, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -231.346837, y: 34.819446, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -231.504771, y: 37.283223, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -231.796547, y: 39.658066, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -232.198126, y: 41.696698, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -232.193767, y: 43.152423, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: -233.670353, y: 45.568782, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: -247.582493, y: 45.495812, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -249.667227, y: 42.842514, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -249.58826, y: 38.815187, z: 0.0, vel: 0.5, rad: 0.8, stop: false} +- point: {x: -249.58826, y: 34.993174, z: 0.0, vel: 0.5, rad: 1.0, stop: false} +- point: {x: -250.797814, y: 32.789915, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666494610.9868476, frame_id: map} + pose: + position: {x: -253.53662, y: 32.560985, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9998286937687794, w: 0.018509000962138693} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_3.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_3.yaml new file mode 100644 index 0000000..97b1ca9 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_3.yaml @@ -0,0 +1,84 @@ +waypoints: +- point: {x: -261.084644, y: 25.106299, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -267.210686, y: 24.487174, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -273.714157, y: 24.216942, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -280.73943, y: 24.197371, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -286.660415, y: 24.152768, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -291.464542, y: 23.895203, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -296.726097, y: 23.847767, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -302.632906, y: 23.786238, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -309.031948, y: 24.093884, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -315.554049, y: 24.216942, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -323.552852, y: 23.724708, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -331.613184, y: 24.216942, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -340.011637, y: 24.599054, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -347.787399, y: 24.612969, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -352.512079, y: 24.544178, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -359.531152, y: 24.693069, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -365.78969, y: 24.599191, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -375.637301, y: 24.635168, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -381.936604, y: 24.109348, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -385.203509, y: 23.981651, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -396.339447, y: 23.239943, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -404.622009, y: 22.94455, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -410.163652, y: 22.799583, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -419.058847, y: 22.392409, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -422.821955, y: 22.212243, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -427.469435, y: 22.220317, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -437.718629, y: 21.536149, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -445.864096, y: 20.845416, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -454.063252, y: 20.804665, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -461.51272, y: 20.53732, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -468.001867, y: 20.498208, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -472.69976, y: 20.525187, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -477.467957, y: 20.554061, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -482.298323, y: 20.463658, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -487.774427, y: 20.217541, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -493.619706, y: 20.032953, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -498.726634, y: 19.663778, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -503.833562, y: 19.356131, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -508.741607, y: 18.673968, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -513.419998, y: 17.640137, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -516.439528, y: 16.782203, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -521.246972, y: 16.615719, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -525.502768, y: 17.645885, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -526.633659, y: 21.449477, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -526.503166, y: 29.100927, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -526.695646, y: 34.975355, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -526.440251, y: 39.554096, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -526.129355, y: 42.504156, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -524.196191, y: 44.731497, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -519.615433, y: 45.109725, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -514.026067, y: 45.614029, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -508.394676, y: 45.950231, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -502.972033, y: 46.055406, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -496.687764, y: 46.175181, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -491.509825, y: 46.328779, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -485.014307, y: 46.391466, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -478.324903, y: 46.231843, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -470.761459, y: 46.534443, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -465.549122, y: 46.670207, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -459.211722, y: 46.876885, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -454.425711, y: 47.201971, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -448.426259, y: 46.859625, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -444.309972, y: 46.893574, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -440.607855, y: 46.916813, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -435.018004, y: 47.17072, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -429.261022, y: 47.925421, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -423.587605, y: 48.177573, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -417.376215, y: 48.176948, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -413.027875, y: 48.139494, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -408.190001, y: 48.288813, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -401.96904, y: 48.457892, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -396.058063, y: 48.456337, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -390.998677, y: 48.514533, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -386.356163, y: 48.128242, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.533166, y: 47.099655, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.370965, y: 49.126063, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: -379.63396, y: 57.591197, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -379.460435, y: 62.156356, z: 0.0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666496150.059658, frame_id: map} + pose: + position: {x: -378.673846, y: 64.77052, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6808672023427723, w: 0.732406890173711} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_4.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_4.yaml new file mode 100644 index 0000000..9a2178c --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_4.yaml @@ -0,0 +1,46 @@ +waypoints: +- point: {x: -380.394722, y: 71.704364, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.214226, y: 74.909309, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.174742, y: 80.096846, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.181996, y: 83.448848, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.34631, y: 87.362533, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.276098, y: 93.34772, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.157839, y: 100.376139, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.522252, y: 104.822308, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.581655, y: 110.05979, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.364453, y: 115.497748, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.444223, y: 119.082618, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.43964, y: 123.129382, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.111881, y: 128.390948, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.159295, y: 131.955867, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -381.287123, y: 134.396899, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.992375, y: 135.259747, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -388.240759, y: 134.995005, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -393.400367, y: 134.825837, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -400.431366, y: 134.823649, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -408.792642, y: 134.648237, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -420.662145, y: 134.765178, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -432.473178, y: 134.706708, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -444.927386, y: 134.414356, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -456.212185, y: 134.531297, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -468.607922, y: 134.355885, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -476.796732, y: 134.546887, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -484.746706, y: 134.580717, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -492.121576, y: 134.580717, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -498.177089, y: 134.343909, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -504.37423, y: 134.191459, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -510.083633, y: 134.360627, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -518.709842, y: 134.262488, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -528.658445, y: 134.741938, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -538.607047, y: 134.80187, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -547.3726, y: 134.60292, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -556.681108, y: 134.401655, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -566.392145, y: 134.351338, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -575.345194, y: 134.114445, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -582.962469, y: 134.19548, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -588.930261, y: 136.027109, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666497569.7515693, frame_id: map} + pose: + position: {x: -592.510885943929, y: 138.8129128736552, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6952399520376623, w: 0.718777718832929} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_5.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_5.yaml new file mode 100644 index 0000000..9a6f186 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_5.yaml @@ -0,0 +1,29 @@ +waypoints: +- point: {x: 9.67825, y: 0.140065, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 17.3371, y: 0.964738, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 22.2638, y: 1.19774, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 29.724292, y: 1.413955, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 37.392, y: 1.57617, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 46.1511, y: 1.94883, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 54.483, y: 3.18138, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 61.0413, y: 4.44718, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 65.8479, y: 5.15023, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 72.7584, y: 6.25933, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 79.928854, y: 6.845006, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 86.860325, y: 7.222229, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 93.508878, y: 7.175076, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 99.591598, y: 7.175076, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 105.284, y: 7.29065, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 110.955438, y: 7.363687, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 117.038157, y: 8.118133, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 123.403793, y: 8.778273, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 128.684914, y: 9.768483, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 133.588812, y: 10.900152, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 138.074, y: 11.7053, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 142.746, y: 12.4801, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 149.677, y: 10.0145, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666498137.866959, frame_id: map} + pose: + position: {x: 151.43617, y: 6.019831, z: 0} + orientation: {x: -0.0, y: 0.0, z: -0.6687790883343118, w: 0.743461183254867} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_6.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_6.yaml new file mode 100644 index 0000000..ebbeead --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_6.yaml @@ -0,0 +1,39 @@ +waypoints: +- point: {x: 17.276014, y: -0.886464, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 24.757274, y: -0.566752, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 32.033, y: -0.147614, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 41.9788, y: 0.893304, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 51.932791, y: 1.799117, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 61.140496, y: 2.182771, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 69.580892, y: 2.182771, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 76.870325, y: 1.223635, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 82.816967, y: 0.328442, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 87.2669, y: -1.07207, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 93.239578, y: -2.676851, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 100.081414, y: -4.595122, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 105.941, y: -6.06026, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 111.333, y: -7.54676, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 118.078, y: -8.93664, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 126.937219, y: -10.66965, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 134.674249, y: -11.500901, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 142.667048, y: -11.75667, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 149.754, y: -12.0621, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 157.113, y: -12.0096, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 162.104, y: -12.7223, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 165.132, y: -11.3643, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 170.579, y: -10.1581, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 176.876229, y: -8.048012, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 183.702, y: -5.88755, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 190.432016, y: -3.508102, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 196.568, y: -0.608021, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 200.949, y: 1.09074, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 205.714248, y: 2.758253, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 209.229, y: 5.09364, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 210.481, y: 7.34948, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 212.823, y: 9.60237, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 215.445, y: 8.90903, z: 0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666498996.6713529, frame_id: map} + pose: + position: {x: 216.76727, y: 6.666979, z: 0} + orientation: {x: -0.0, y: 0.0, z: -0.4444870197741531, w: 0.8957852919379128} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_7.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_7.yaml new file mode 100644 index 0000000..3db6ccf --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_7.yaml @@ -0,0 +1,72 @@ +waypoints: +- point: {x: 5.3636, y: 0.0904167, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.5044, y: 0.465055, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 16.699, y: 1.24866, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 23.9469, y: 1.59342, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 27.3978, y: 1.22125, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 32.4584, y: -0.0330052, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 36.0657, y: -0.64817, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 39.5796, y: -0.823233, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 45.0522, y: -1.65752, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 51.70582, y: -1.967532, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 58.020918, y: -2.126736, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 63.4809, y: -2.7043, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 69.324413, y: -4.780138, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 74.312809, y: -6.531384, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 79.301206, y: -7.433541, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 85.92, y: -8.20992, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 91.0165, y: -9.25405, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 95.6054, y: -9.6805, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 99.7147, y: -9.56832, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 103.149, y: -9.34752, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 106.116, y: -7.88057, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 109.569, y: -6.06586, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 112.919, y: -3.91319, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 116.502, y: -2.12353, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 119.759, y: 0.0310771, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 123.029, y: 2.09065, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 127.212, y: 4.48471, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 130.763, y: 6.50064, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 134.614, y: 8.44767, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 137.107, y: 9.20638, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 140.624, y: 10.5317, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 143.961, y: 10.5781, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 147.346, y: 9.77895, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 150.397, y: 8.73421, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 154.66, y: 7.48929, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 158.342, y: 6.02823, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 162.934, y: 4.55966, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 166.195, y: 3.45894, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 169.993, y: 2.04407, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 173.566, y: 0.878988, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 177.541, y: -0.293789, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 182.438, y: -1.74787, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 185.46, y: -2.76484, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 188.404, y: -3.36537, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 194.471, y: -4.88014, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 199.113, y: -5.33859, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 202.886, y: -5.88745, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 206.441, y: -7.31497, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 208.486, y: -10.3279, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 209.529, y: -14.663, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 210.145, y: -18.5102, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 210.708, y: -21.7332, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 210.066, y: -26.0123, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 208.603, y: -31.8163, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 208.456, y: -36.4555, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 207.626, y: -43.7698, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 206.67, y: -49.5498, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 205.592, y: -54.7511, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 204.77, y: -59.0512, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 206.924, y: -64.381, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 208.642, y: -68.1098, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 210.39, y: -72.1318, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 212.264, y: -75.1983, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 216.875, y: -77.5158, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: 225.351, y: -80.4098, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: 227.891984, y: -77.714962, z: 0.0, vel: 1, rad: 0.5, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500443.4820855, frame_id: map} + pose: + position: {x: 227.823711, y: -74.164762, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.5788893188481334, w: 0.815406129804985} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_8.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_8.yaml new file mode 100644 index 0000000..151c793 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_8.yaml @@ -0,0 +1,25 @@ +waypoints: +- point: {x: 14.9492, y: 0.871575, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 19.6856, y: 0.632644, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 24.9351, y: 0.233624, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 32.0594, y: -0.17328, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 39.5993, y: -0.453472, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 46.9868, y: -1.03966, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 54.2481, y: -1.22557, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 62.8625, y: -1.11575, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 71.0413, y: -1.23109, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 79.8398, y: -1.10049, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 88.495, y: -0.986142, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 96.6576, y: -0.955216, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 103.025, y: -0.811471, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 109.904315, y: -1.289815, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: 116.139361, y: -5.100952, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 121.485, y: -8.93011, z: 0, vel: 1, rad: 1, stop: true} +- point: {x: 127.70905, y: -9.380839, z: 0.0, vel: 1, rad: 1, stop: true} +- point: {x: 142.110378, y: -9.242956, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 145.37988, y: -11.044519, z: 0.0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500880.699932, frame_id: map} + pose: + position: {x: 145.605235, y: -14.406034, z: 0} + orientation: {x: -0.0, y: 0.0, z: -0.7071067811865476, w: 0.7071067811865476} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_9.yaml b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_9.yaml new file mode 100644 index 0000000..f481ebf --- /dev/null +++ b/src/tsukuba2022/config/waypoints/tsukuba/waypoints_tsukuba_9.yaml @@ -0,0 +1,38 @@ +waypoints: +- point: {x: -229.450346, y: 36.265549, z: 0, vel: 1, rad: 1.0, stop: false} +- point: {x: -229.478325, y: 31.425174, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -229.310451, y: 25.941282, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -229.03066, y: 19.841851, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.806828, y: 14.413916, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.918744, y: 9.097898, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.862786, y: 2.382928, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.638954, y: -3.324797, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.471079, y: -9.704018, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.582996, y: -16.139198, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.610975, y: -22.714273, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.694912, y: -28.505935, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -228.582996, y: -35.66857, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -224.442097, y: -42.943121, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -215.376887, y: -42.719289, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -207.207007, y: -42.215666, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -198.92521, y: -42.159708, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -190.643414, y: -41.712043, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -182.361617, y: -41.320337, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -173.072575, y: -41.264379, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -164.566946, y: -40.872672, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -154.886197, y: -40.536923, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -148.115269, y: -40.64884, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -142.295628, y: -40.984588, z: 0.0, vel: 1, rad: 1, stop: true} +- point: {x: -135.300868, y: -40.480965, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -127.019071, y: -40.592881, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -118.28961, y: -40.201175, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -109.672065, y: -40.201175, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -100.718771, y: -40.033301, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -90.926106, y: -39.529678, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -81.077483, y: -39.641594, z: 0.0, vel: 1, rad: 1.0, stop: false} +- point: {x: -72.236106, y: -39.361804, z: 0.0, vel: 1, rad: 1.0, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500880.699932, frame_id: map} + pose: + position: {x: -66.953131, y: -39.658873, z: 0} + orientation: {x: -0.0, y: 0.0, z: -0.020647941737949912, w: 0.9997868085256908} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/waypoints.yaml b/src/tsukuba2022/config/waypoints/waypoints.yaml index 33c7c83..a3c9691 100644 --- a/src/tsukuba2022/config/waypoints/waypoints.yaml +++ b/src/tsukuba2022/config/waypoints/waypoints.yaml @@ -1,23 +1,8 @@ waypoints: -- point: {x: 3.876438, y: 0.067258, z: 0.00511169, vel: 1, rad: 1, stop: false} -- point: {x: 10.24828, y: 0.067258, z: -0.00192642, vel: 1, rad: 1, stop: false} -- point: {x: 14.343374, y: 0.067258, z: 0.00251579, vel: 1, rad: 1, stop: false} -- point: {x: 15.695671, y: 1.465396, z: 0.0, vel: 1.0, rad: 1.0, stop: false} -- point: {x: 15.731122, y: 6.432358, z: 0.00242996, vel: 1, rad: 1, stop: false} -- point: {x: 15.770729, y: 11.224717, z: 0.0, vel: 1, rad: 1, stop: false} -- point: {x: 15.840833, y: 15.530818, z: 0.0023098, vel: 1, rad: 1, stop: false} -- point: {x: 14.381574, y: 17.020638, z: 0.0, vel: 1, rad: 1, stop: false} -- point: {x: 9.36751, y: 17.0985, z: 0.00177956, vel: 1, rad: 1, stop: false} -- point: {x: 4.640448, y: 17.165799, z: 0.000879288, vel: 1, rad: 1, stop: false} -- point: {x: 3.318711, y: 15.828782, z: 0.0, vel: 1, rad: 1, stop: true} -- point: {x: 4.72936, y: 13.403, z: 0.00301743, vel: 1, rad: 1, stop: false} -- point: {x: 6.72777, y: 10.9204, z: 0.00507927, vel: 1, rad: 1, stop: false} -- point: {x: 8.047505, y: 8.46548, z: 0.00030899, vel: 1, rad: 1, stop: false} -- point: {x: 9.32663, y: 6.47157, z: 0.00183296, vel: 1, rad: 1, stop: false} -- point: {x: 11.210933, y: 3.520583, z: 0.00384521, vel: 1, rad: 1, stop: false} -- point: {x: 10.872753, y: 0.465013, z: 0.00480747, vel: 1, rad: 1, stop: false} +- point: {x: 2.66587, y: 0.0700625, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 8.1709, y: 0.357594, z: 0, vel: 1, rad: 0.8, stop: false} finish_pose: - header: {seq: 0, stamp: 113.132, frame_id: map} - pose: - position: {x: 9.27349, y: 0.143879, z: 0} - orientation: {x: 0, y: 0, z: 0.999983, w: 0.00578372} \ No newline at end of file + header: {seq: 0, stamp: 1668580166.701891002, frame_id: map} + pose: + position: {x: 10.2119, y: 0.455358, z: 0} + orientation: {x: 0, y: 0, z: -0.999671, w: 0.0256456} diff --git a/src/tsukuba2022/config/waypoints/waypoints_202211160629.yaml b/src/tsukuba2022/config/waypoints/waypoints_202211160629.yaml new file mode 100644 index 0000000..a3c9691 --- /dev/null +++ b/src/tsukuba2022/config/waypoints/waypoints_202211160629.yaml @@ -0,0 +1,8 @@ +waypoints: +- point: {x: 2.66587, y: 0.0700625, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 8.1709, y: 0.357594, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1668580166.701891002, frame_id: map} + pose: + position: {x: 10.2119, y: 0.455358, z: 0} + orientation: {x: 0, y: 0, z: -0.999671, w: 0.0256456} diff --git a/src/tsukuba2022/config/waypoints/waypoints_nakaniwa.yaml b/src/tsukuba2022/config/waypoints/waypoints_nakaniwa.yaml deleted file mode 100644 index 03e07a4..0000000 --- a/src/tsukuba2022/config/waypoints/waypoints_nakaniwa.yaml +++ /dev/null @@ -1,33 +0,0 @@ -waypoints: -- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 17.334, y: -0.0478781, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 25.9562, y: -0.150485, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 34.8965, y: -2.35386, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 43.2493, y: -4.61744, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 52.0631, y: -4.78826, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 53.2674, y: 7.98859, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 53.0977, y: 20.0885, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 52.225629, y: 42.300035, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 51.282771, y: 54.557184, z: 0, vel: 1, rad: 0.6, stop: false} -- point: {x: 37.976717, y: 54.326666, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 27.652743, y: 54.28618, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 16.033212, y: 54.367152, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 5.061459, y: 53.516942, z: 0, vel: 1, rad: 0.5, stop: true} -- point: {x: 6.397503, y: 50.520966, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 9.777492, y: 43.91924, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 12.326369, y: 38.156927, z: 0.0, vel: 1.0, rad: 0.4, stop: false} -- point: {x: 14.7664, y: 33.8169, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 18.112117, y: 26.331971, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 20.711327, y: 20.328163, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 22.614973, y: 15.935132, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 24.408794, y: 12.164447, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 29.131302, y: 2.572996, z: 0, vel: 0.3, rad: 0.3, stop: false} -- point: {x: 28.801589, y: 0.126455, z: 0, vel: 0.3, rad: 0.5, stop: false} -- point: {x: 19.9255, y: 0.305246, z: 0, vel: 1, rad: 1.0, stop: false} -- point: {x: 9.62386, y: 1.54376, z: 0, vel: 1, rad: 1.0, stop: false} -finish_pose: - header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} - pose: - position: {x: -0.0241434, y: 1.60681, z: 0} - orientation: {x: 0, y: 0, z: 0.999995, w: 0.00303693} \ No newline at end of file diff --git a/src/tsukuba2022/config/waypoints/waypoints_sim_nakaniwa.yaml b/src/tsukuba2022/config/waypoints/waypoints_sim_nakaniwa.yaml deleted file mode 100644 index 33c7c83..0000000 --- a/src/tsukuba2022/config/waypoints/waypoints_sim_nakaniwa.yaml +++ /dev/null @@ -1,23 +0,0 @@ -waypoints: -- point: {x: 3.876438, y: 0.067258, z: 0.00511169, vel: 1, rad: 1, stop: false} -- point: {x: 10.24828, y: 0.067258, z: -0.00192642, vel: 1, rad: 1, stop: false} -- point: {x: 14.343374, y: 0.067258, z: 0.00251579, vel: 1, rad: 1, stop: false} -- point: {x: 15.695671, y: 1.465396, z: 0.0, vel: 1.0, rad: 1.0, stop: false} -- point: {x: 15.731122, y: 6.432358, z: 0.00242996, vel: 1, rad: 1, stop: false} -- point: {x: 15.770729, y: 11.224717, z: 0.0, vel: 1, rad: 1, stop: false} -- point: {x: 15.840833, y: 15.530818, z: 0.0023098, vel: 1, rad: 1, stop: false} -- point: {x: 14.381574, y: 17.020638, z: 0.0, vel: 1, rad: 1, stop: false} -- point: {x: 9.36751, y: 17.0985, z: 0.00177956, vel: 1, rad: 1, stop: false} -- point: {x: 4.640448, y: 17.165799, z: 0.000879288, vel: 1, rad: 1, stop: false} -- point: {x: 3.318711, y: 15.828782, z: 0.0, vel: 1, rad: 1, stop: true} -- point: {x: 4.72936, y: 13.403, z: 0.00301743, vel: 1, rad: 1, stop: false} -- point: {x: 6.72777, y: 10.9204, z: 0.00507927, vel: 1, rad: 1, stop: false} -- point: {x: 8.047505, y: 8.46548, z: 0.00030899, vel: 1, rad: 1, stop: false} -- point: {x: 9.32663, y: 6.47157, z: 0.00183296, vel: 1, rad: 1, stop: false} -- point: {x: 11.210933, y: 3.520583, z: 0.00384521, vel: 1, rad: 1, stop: false} -- point: {x: 10.872753, y: 0.465013, z: 0.00480747, vel: 1, rad: 1, stop: false} -finish_pose: - header: {seq: 0, stamp: 113.132, frame_id: map} - pose: - position: {x: 9.27349, y: 0.143879, z: 0} - orientation: {x: 0, y: 0, z: 0.999983, w: 0.00578372} \ No newline at end of file diff --git a/src/tsukuba2022/launch/buildmap_from_bag.launch b/src/tsukuba2022/launch/buildmap_from_bag.launch index bd635a5..a232c79 100644 --- a/src/tsukuba2022/launch/buildmap_from_bag.launch +++ b/src/tsukuba2022/launch/buildmap_from_bag.launch @@ -2,9 +2,16 @@ + + + + + + + @@ -14,6 +21,18 @@ + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/buildmap_teleop_joy.launch b/src/tsukuba2022/launch/buildmap_teleop_joy.launch index acdc48d..fbb359d 100644 --- a/src/tsukuba2022/launch/buildmap_teleop_joy.launch +++ b/src/tsukuba2022/launch/buildmap_teleop_joy.launch @@ -7,7 +7,7 @@ - + @@ -40,6 +40,6 @@ - + diff --git a/src/tsukuba2022/launch/motor.launch b/src/tsukuba2022/launch/motor.launch index e41ec65..feb8d78 100644 --- a/src/tsukuba2022/launch/motor.launch +++ b/src/tsukuba2022/launch/motor.launch @@ -1,27 +1,22 @@ - - + - - - - - - - + + + + - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/src/tsukuba2022/launch/segmentation.launch b/src/tsukuba2022/launch/segmentation.launch new file mode 100644 index 0000000..d31d460 --- /dev/null +++ b/src/tsukuba2022/launch/segmentation.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/sensors.launch b/src/tsukuba2022/launch/sensors.launch new file mode 100644 index 0000000..fee8690 --- /dev/null +++ b/src/tsukuba2022/launch/sensors.launch @@ -0,0 +1,93 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/start.launch b/src/tsukuba2022/launch/start.launch index 6c5fd1e..e85ef9e 100644 --- a/src/tsukuba2022/launch/start.launch +++ b/src/tsukuba2022/launch/start.launch @@ -1,140 +1,31 @@ - + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + - - - - - - - - - - - - + + + + + + + + diff --git a/src/tsukuba2022/launch/start_sim.launch b/src/tsukuba2022/launch/start_sim.launch index a0d655f..58eea84 100644 --- a/src/tsukuba2022/launch/start_sim.launch +++ b/src/tsukuba2022/launch/start_sim.launch @@ -12,6 +12,7 @@ + @@ -22,25 +23,16 @@ + - - - - - - - + + - - - - - - + @@ -55,6 +47,7 @@ + @@ -63,5 +56,4 @@ - diff --git a/src/tsukuba2022/launch/waypoint_navigation.launch b/src/tsukuba2022/launch/waypoint_navigation.launch index a896ca9..07c43b5 100644 --- a/src/tsukuba2022/launch/waypoint_navigation.launch +++ b/src/tsukuba2022/launch/waypoint_navigation.launch @@ -1,26 +1,27 @@ - - - - - - + + + + + + - - - - - - - - + + + + + + + + + @@ -28,20 +29,26 @@ + + - - - - + + + + + + + + - + diff --git a/src/tsukuba2022/launch/waypoint_navigation_emcl.launch b/src/tsukuba2022/launch/waypoint_navigation_emcl.launch new file mode 100644 index 0000000..34aff0e --- /dev/null +++ b/src/tsukuba2022/launch/waypoint_navigation_emcl.launch @@ -0,0 +1,49 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/launch/waypoint_navigation_multi.launch b/src/tsukuba2022/launch/waypoint_navigation_multi.launch new file mode 100644 index 0000000..4d004e5 --- /dev/null +++ b/src/tsukuba2022/launch/waypoint_navigation_multi.launch @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/tsukuba2022/maps/cpmap.sh b/src/tsukuba2022/maps/cpmap.sh new file mode 100755 index 0000000..a06cd76 --- /dev/null +++ b/src/tsukuba2022/maps/cpmap.sh @@ -0,0 +1,2 @@ +cp $1.pgm $2.pgm +cp $1.yaml $2.yaml diff --git a/src/tsukuba2022/maps/mymap.pgm b/src/tsukuba2022/maps/mymap.pgm index 7bedc78..f75a562 100644 --- a/src/tsukuba2022/maps/mymap.pgm +++ b/src/tsukuba2022/maps/mymap.pgm Binary files differ diff --git a/src/tsukuba2022/maps/mymap.yaml b/src/tsukuba2022/maps/mymap.yaml index ca6f07f..9dd3917 100644 --- a/src/tsukuba2022/maps/mymap.yaml +++ b/src/tsukuba2022/maps/mymap.yaml @@ -1,6 +1,6 @@ image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap.pgm -resolution: 0.050000 -origin: [-60.000000, -60.000000, 0.000000] +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] negate: 0 occupied_thresh: 0.65 free_thresh: 0.196 diff --git a/src/tsukuba2022/maps/mymap_202211160629.pgm b/src/tsukuba2022/maps/mymap_202211160629.pgm new file mode 100644 index 0000000..f75a562 --- /dev/null +++ b/src/tsukuba2022/maps/mymap_202211160629.pgm Binary files differ diff --git a/src/tsukuba2022/maps/mymap_202211160629.yaml b/src/tsukuba2022/maps/mymap_202211160629.yaml new file mode 100644 index 0000000..9dd3917 --- /dev/null +++ b/src/tsukuba2022/maps/mymap_202211160629.yaml @@ -0,0 +1,7 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap.pgm +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/mymap_nakaniwa.pgm b/src/tsukuba2022/maps/mymap_nakaniwa.pgm deleted file mode 100644 index 86ebccd..0000000 --- a/src/tsukuba2022/maps/mymap_nakaniwa.pgm +++ /dev/null Binary files differ diff --git a/src/tsukuba2022/maps/mymap_nakaniwa.yaml b/src/tsukuba2022/maps/mymap_nakaniwa.yaml deleted file mode 100644 index deebdb7..0000000 --- a/src/tsukuba2022/maps/mymap_nakaniwa.yaml +++ /dev/null @@ -1,7 +0,0 @@ -image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap_nakaniwa.pgm -resolution: 0.050000 -origin: [-60.000000, -60.000000, 0.000000] -negate: 0 -occupied_thresh: 0.65 -free_thresh: 0.196 - diff --git a/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm b/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm deleted file mode 100644 index 7bedc78..0000000 --- a/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm +++ /dev/null Binary files differ diff --git a/src/tsukuba2022/maps/mymap_sim_nakaniwa.yaml b/src/tsukuba2022/maps/mymap_sim_nakaniwa.yaml deleted file mode 100644 index e95a921..0000000 --- a/src/tsukuba2022/maps/mymap_sim_nakaniwa.yaml +++ /dev/null @@ -1,7 +0,0 @@ -image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/mymap_sim_nakaniwa.pgm -resolution: 0.050000 -origin: [-60.000000, -60.000000, 0.000000] -negate: 0 -occupied_thresh: 0.65 -free_thresh: 0.196 - diff --git a/src/tsukuba2022/maps/nakaniwa/merged-nakaniwa_1-2.pgm b/src/tsukuba2022/maps/nakaniwa/merged-nakaniwa_1-2.pgm new file mode 100644 index 0000000..0ae09cc --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/merged-nakaniwa_1-2.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/merged-nakaniwa_1-2.yaml b/src/tsukuba2022/maps/nakaniwa/merged-nakaniwa_1-2.yaml new file mode 100644 index 0000000..579dfdb --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/merged-nakaniwa_1-2.yaml @@ -0,0 +1,6 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/nakaniwa/merged-nakaniwa_1-2.pgm +resolution: 0.05 +origin: [-50.0, -50.3947385034915, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa.pgm new file mode 100644 index 0000000..86ebccd --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa.yaml new file mode 100644 index 0000000..c152407 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa.yaml @@ -0,0 +1,7 @@ +image: ./mymap_nakaniwa.pgm +resolution: 0.050000 +origin: [-60.000000, -60.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1.pgm new file mode 100644 index 0000000..ae968dc --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1.yaml new file mode 100644 index 0000000..234dc89 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1.yaml @@ -0,0 +1,7 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1.pgm +resolution: 0.050000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1109.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1109.pgm new file mode 100644 index 0000000..60586df --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1109.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1109.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1109.yaml new file mode 100644 index 0000000..4b2b14e --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_1109.yaml @@ -0,0 +1,7 @@ +image: ./mymap_nakaniwa_1109.pgm +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_2.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_2.pgm new file mode 100644 index 0000000..73d7b42 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_2.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_2.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_2.yaml new file mode 100644 index 0000000..9b6f2d2 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_2.yaml @@ -0,0 +1,7 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_2.pgm +resolution: 0.050000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim.pgm new file mode 100644 index 0000000..7bedc78 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim.yaml new file mode 100644 index 0000000..2f6898c --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim.yaml @@ -0,0 +1,7 @@ +image: ./mymap_nakaniwa_sim.pgm +resolution: 0.050000 +origin: [-60.000000, -60.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_1.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_1.pgm new file mode 100644 index 0000000..78798d3 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_1.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_1.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_1.yaml new file mode 100644 index 0000000..565c916 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_1.yaml @@ -0,0 +1,7 @@ +image: ./mymap_nakaniwa_sim_1.pgm +resolution: 0.050000 +origin: [-60.000000, -60.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_2.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_2.pgm new file mode 100644 index 0000000..e897525 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_2.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_2.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_2.yaml new file mode 100644 index 0000000..901cd59 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_sim_2.yaml @@ -0,0 +1,7 @@ +image: ./mymap_nakaniwa_sim_2.pgm +resolution: 0.050000 +origin: [-60.000000, -60.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_trim.pgm b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_trim.pgm new file mode 100644 index 0000000..4361968 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_trim.pgm Binary files differ diff --git a/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_trim.yaml b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_trim.yaml new file mode 100644 index 0000000..80ce244 --- /dev/null +++ b/src/tsukuba2022/maps/nakaniwa/mymap_nakaniwa_trim.yaml @@ -0,0 +1,6 @@ +image: ./mymap_nakaniwa_trim.pgm +resolution: 0.05 +origin: [28.170469620170707, -28.544742473573685, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/maps/setmap.sh b/src/tsukuba2022/maps/setmap.sh new file mode 100755 index 0000000..d89f860 --- /dev/null +++ b/src/tsukuba2022/maps/setmap.sh @@ -0,0 +1,2 @@ +cp $1.pgm mymap.pgm +cp $1.yaml mymap.yaml diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_1.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_1.pgm new file mode 100644 index 0000000..fd554ed --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_1.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_1.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_1.yaml new file mode 100644 index 0000000..6074276 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_1.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_1.pgm +resolution: 0.100000 +origin: [-110.800000, -78.800000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_2.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_2.pgm new file mode 100644 index 0000000..dbdb838 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_2.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_2.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_2.yaml new file mode 100644 index 0000000..4dd51ac --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_2.yaml @@ -0,0 +1,6 @@ +image: ./mymap_tsukuba_2.pgm +resolution: 0.1 +origin: [-288.3931311734531, -87.22861015928352, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_3.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_3.pgm new file mode 100644 index 0000000..bea8647 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_3.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_3.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_3.yaml new file mode 100644 index 0000000..75422f2 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_3.yaml @@ -0,0 +1,6 @@ +image: ./mymap_tsukuba_3.pgm +resolution: 0.1 +origin: [-550.6649715593369, -29.044654528977503, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_4.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_4.pgm new file mode 100644 index 0000000..208247f --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_4.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_4.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_4.yaml new file mode 100644 index 0000000..57d92e9 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_4.yaml @@ -0,0 +1,6 @@ +image: ./mymap_tsukuba_4.pgm +resolution: 0.1 +origin: [-606.5557738478564, 58.956719886505816, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_5.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_5.pgm new file mode 100644 index 0000000..03d2701 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_5.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_5.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_5.yaml new file mode 100644 index 0000000..96f9ed2 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_5.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_5.pgm +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_6.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_6.pgm new file mode 100644 index 0000000..1f599d6 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_6.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_6.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_6.yaml new file mode 100644 index 0000000..17122d6 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_6.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_6.pgm +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_7.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_7.pgm new file mode 100644 index 0000000..17b4003 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_7.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_7.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_7.yaml new file mode 100644 index 0000000..6cd3e5a --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_7.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_7.pgm +resolution: 0.100000 +origin: [-50.000000, -117.200000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_8.pgm b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_8.pgm new file mode 100644 index 0000000..2020802 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_8.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_8.yaml b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_8.yaml new file mode 100644 index 0000000..4291203 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/edited/mymap_tsukuba_8.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_8.pgm +resolution: 0.100000 +origin: [-50.000000, -66.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old.pgm b/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old.pgm new file mode 100644 index 0000000..5fb1a07 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old.yaml b/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old.yaml new file mode 100644 index 0000000..3233096 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_1_edited.pgm +resolution: 0.050000 +origin: [-82.400000, -74.400000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old_edited.pgm b/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old_edited.pgm new file mode 100644 index 0000000..97bd1d5 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/old/mymap_tsukuba_1_old_edited.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_1.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_1.pgm new file mode 100644 index 0000000..3e42d70 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_1.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_1.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_1.yaml new file mode 100644 index 0000000..6074276 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_1.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_1.pgm +resolution: 0.100000 +origin: [-110.800000, -78.800000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_2.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_2.pgm new file mode 100644 index 0000000..a733b2a --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_2.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_2.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_2.yaml new file mode 100644 index 0000000..c208466 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_2.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_2.pgm +resolution: 0.100000 +origin: [-50.000000, -146.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_3.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_3.pgm new file mode 100644 index 0000000..bdbc38a --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_3.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_3.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_3.yaml new file mode 100644 index 0000000..11084f6 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_3.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_3.pgm +resolution: 0.100000 +origin: [-62.800000, -315.600000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_4.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_4.pgm new file mode 100644 index 0000000..bfc561a --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_4.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_4.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_4.yaml new file mode 100644 index 0000000..b70cf11 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_4.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_4.pgm +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_5.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_5.pgm new file mode 100644 index 0000000..a5479fd --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_5.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_5.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_5.yaml new file mode 100644 index 0000000..96f9ed2 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_5.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_5.pgm +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_6.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_6.pgm new file mode 100644 index 0000000..99f13fd --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_6.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_6.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_6.yaml new file mode 100644 index 0000000..17122d6 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_6.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_6.pgm +resolution: 0.100000 +origin: [-50.000000, -50.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_7.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_7.pgm new file mode 100644 index 0000000..be01057 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_7.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_7.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_7.yaml new file mode 100644 index 0000000..6cd3e5a --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_7.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_7.pgm +resolution: 0.100000 +origin: [-50.000000, -117.200000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_8.pgm b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_8.pgm new file mode 100644 index 0000000..3c177e4 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_8.pgm Binary files differ diff --git a/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_8.yaml b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_8.yaml new file mode 100644 index 0000000..4291203 --- /dev/null +++ b/src/tsukuba2022/maps/tsukuba/raw/mymap_tsukuba_8.yaml @@ -0,0 +1,7 @@ +image: ./mymap_tsukuba_8.pgm +resolution: 0.100000 +origin: [-50.000000, -66.000000, 0.000000] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 + diff --git a/src/tsukuba2022/meshes/left_wheel.dae b/src/tsukuba2022/meshes/left_wheel.dae deleted file mode 100644 index 59f8c6b..0000000 --- a/src/tsukuba2022/meshes/left_wheel.dae +++ /dev/null @@ -1,174 +0,0 @@ - - - - - 2022-05-02T17:50:12 - 2022-05-02T17:50:12 - - Z_UP - - - - - - - - - - - - - - - - - - 0.913725 0.913725 0.913725 1 - - - 1 1 1 1 - - - 1 - - - - - - 1 - - - - - - - - - - 0.301961 0.301961 0.301961 1 - - - 1 1 1 1 - - - 1 - - - - - - 1 - - - - - - - - - - - 1.60781e-17 0.05 -0.01 1.60781e-17 0.05 0.01 -0.00156793 0.0500822 0.01 0.015 0.065 0.01 0.015 0.065 -0.01 0.0149178 0.0665679 -0.01 -0.00311868 0.0503278 0.01 -0.00156793 0.0500822 -0.01 -0.00463525 0.0507342 0.01 -0.00311868 0.0503278 -0.01 -0.00463525 0.0507342 -0.01 -0.00610105 0.0512968 0.01 -0.0075 0.0520096 0.01 -0.00610105 0.0512968 -0.01 -0.00881678 0.0528647 0.01 -0.0075 0.0520096 -0.01 -0.00881678 0.0528647 -0.01 -0.010037 0.0538528 0.01 -0.0111472 0.054963 0.01 -0.010037 0.0538528 -0.01 -0.0121353 0.0561832 0.01 -0.0111472 0.054963 -0.01 -0.0121353 0.0561832 -0.01 -0.0129904 0.0575 0.01 -0.0137032 0.0588989 0.01 -0.0129904 0.0575 -0.01 -0.0142658 0.0603647 0.01 -0.0137032 0.0588989 -0.01 -0.0142658 0.0603647 -0.01 -0.0146722 0.0618813 0.01 -0.0149178 0.0634321 0.01 -0.0146722 0.0618813 -0.01 -0.015 0.065 0.01 -0.0149178 0.0634321 -0.01 -0.015 0.065 -0.01 0.00156793 0.0500822 -0.01 0.00311868 0.0503278 -0.01 0.00156793 0.0500822 0.01 0.00311868 0.0503278 0.01 0.00463525 0.0507342 -0.01 0.00610105 0.0512968 -0.01 0.00463525 0.0507342 0.01 0.0075 0.0520096 -0.01 0.00610105 0.0512968 0.01 0.0075 0.0520096 0.01 0.00881678 0.0528647 -0.01 0.010037 0.0538528 -0.01 0.00881678 0.0528647 0.01 0.0111472 0.054963 -0.01 0.010037 0.0538528 0.01 0.0111472 0.054963 0.01 0.0121353 0.0561832 -0.01 0.0129904 0.0575 -0.01 0.0121353 0.0561832 0.01 0.0137032 0.0588989 -0.01 0.0129904 0.0575 0.01 0.0137032 0.0588989 0.01 0.0142658 0.0603647 -0.01 0.0146722 0.0618813 -0.01 0.0142658 0.0603647 0.01 0.0149178 0.0634321 -0.01 0.0146722 0.0618813 0.01 0.0149178 0.0634321 0.01 0.0146722 0.0681187 0.01 0.0149178 0.0665679 0.01 0.0146722 0.0681187 -0.01 0.0129904 0.0725 0.01 0.0137032 0.0711011 0.01 0.0129904 0.0725 -0.01 0.0142658 0.0696353 0.01 0.0142658 0.0696353 -0.01 0.0137032 0.0711011 -0.01 0.0111472 0.075037 0.01 0.010037 0.0761472 -0.01 0.010037 0.0761472 0.01 0.0121353 0.0738168 -0.01 0.0111472 0.075037 -0.01 0.0121353 0.0738168 0.01 0.00610105 0.0787032 -0.01 0.00610105 0.0787032 0.01 0.0075 0.0779904 0.01 0.0075 0.0779904 -0.01 0.00881678 0.0771353 0.01 0.00881678 0.0771353 -0.01 0.00156793 0.0799178 0.01 0.00311868 0.0796722 0.01 0.00156793 0.0799178 -0.01 0.00463525 0.0792658 0.01 0.00463525 0.0792658 -0.01 0.00311868 0.0796722 -0.01 -0.00156793 0.0799178 0.01 -0.00311868 0.0796722 -0.01 -0.00311868 0.0796722 0.01 -4.24915e-18 0.08 -0.01 -0.00156793 0.0799178 -0.01 -4.24915e-18 0.08 0.01 -0.0075 0.0779904 -0.01 -0.0075 0.0779904 0.01 -0.00610105 0.0787032 0.01 -0.00610105 0.0787032 -0.01 -0.00463525 0.0792658 0.01 -0.00463525 0.0792658 -0.01 -0.0111472 0.075037 0.01 -0.010037 0.0761472 0.01 -0.0111472 0.075037 -0.01 -0.00881678 0.0771353 0.01 -0.00881678 0.0771353 -0.01 -0.010037 0.0761472 -0.01 -0.0121353 0.0738168 -0.01 -0.0121353 0.0738168 0.01 -0.0129904 0.0725 -0.01 -0.0129904 0.0725 0.01 -0.0137032 0.0711011 0.01 -0.0137032 0.0711011 -0.01 -0.0142658 0.0696353 -0.01 -0.0142658 0.0696353 0.01 -0.0146722 0.0681187 -0.01 -0.0146722 0.0681187 0.01 -0.0149178 0.0665679 0.01 -0.0149178 0.0665679 -0.01 0.0459619 0.0309619 -0.01 0.0459619 0.0309619 0.01 0.044394 0.0310441 0.01 0.0609619 0.0459619 0.01 0.0609619 0.0459619 -0.01 0.0608798 0.0475299 -0.01 0.0428433 0.0312897 0.01 0.044394 0.0310441 -0.01 0.0413267 0.0316961 0.01 0.0428433 0.0312897 -0.01 0.0413267 0.0316961 -0.01 0.0398609 0.0322588 0.01 0.0384619 0.0329716 0.01 0.0398609 0.0322588 -0.01 0.0371452 0.0338267 0.01 0.0384619 0.0329716 -0.01 0.0371452 0.0338267 -0.01 0.035925 0.0348148 0.01 0.0348148 0.035925 0.01 0.035925 0.0348148 -0.01 0.0338267 0.0371452 0.01 0.0348148 0.035925 -0.01 0.0338267 0.0371452 -0.01 0.0329716 0.0384619 0.01 0.0322588 0.0398609 0.01 0.0329716 0.0384619 -0.01 0.0316961 0.0413267 0.01 0.0322588 0.0398609 -0.01 0.0316961 0.0413267 -0.01 0.0312897 0.0428433 0.01 0.0310441 0.044394 0.01 0.0312897 0.0428433 -0.01 0.0309619 0.0459619 0.01 0.0310441 0.044394 -0.01 0.0309619 0.0459619 -0.01 0.0475299 0.0310441 -0.01 0.0490806 0.0312897 -0.01 0.0475299 0.0310441 0.01 0.0490806 0.0312897 0.01 0.0505972 0.0316961 -0.01 0.052063 0.0322588 -0.01 0.0505972 0.0316961 0.01 0.0534619 0.0329716 -0.01 0.052063 0.0322588 0.01 0.0534619 0.0329716 0.01 0.0547787 0.0338267 -0.01 0.0559989 0.0348148 -0.01 0.0547787 0.0338267 0.01 0.0571091 0.035925 -0.01 0.0559989 0.0348148 0.01 0.0571091 0.035925 0.01 0.0580972 0.0371452 -0.01 0.0589523 0.0384619 -0.01 0.0580972 0.0371452 0.01 0.0596651 0.0398609 -0.01 0.0589523 0.0384619 0.01 0.0596651 0.0398609 0.01 0.0602278 0.0413267 -0.01 0.0606342 0.0428433 -0.01 0.0602278 0.0413267 0.01 0.0608798 0.044394 -0.01 0.0606342 0.0428433 0.01 0.0608798 0.044394 0.01 0.0606342 0.0490806 0.01 0.0608798 0.0475299 0.01 0.0606342 0.0490806 -0.01 0.0589523 0.0534619 0.01 0.0596651 0.052063 0.01 0.0589523 0.0534619 -0.01 0.0602278 0.0505972 0.01 0.0602278 0.0505972 -0.01 0.0596651 0.052063 -0.01 0.0571091 0.0559989 0.01 0.0559989 0.0571091 -0.01 0.0559989 0.0571091 0.01 0.0580972 0.0547787 -0.01 0.0571091 0.0559989 -0.01 0.0580972 0.0547787 0.01 0.052063 0.0596651 -0.01 0.052063 0.0596651 0.01 0.0534619 0.0589523 0.01 0.0534619 0.0589523 -0.01 0.0547787 0.0580972 0.01 0.0547787 0.0580972 -0.01 0.0475299 0.0608798 0.01 0.0490806 0.0606342 0.01 0.0475299 0.0608798 -0.01 0.0505972 0.0602278 0.01 0.0505972 0.0602278 -0.01 0.0490806 0.0606342 -0.01 0.044394 0.0608798 0.01 0.0428433 0.0606342 -0.01 0.0428433 0.0606342 0.01 0.0459619 0.0609619 -0.01 0.044394 0.0608798 -0.01 0.0459619 0.0609619 0.01 0.0384619 0.0589523 -0.01 0.0384619 0.0589523 0.01 0.0398609 0.0596651 0.01 0.0398609 0.0596651 -0.01 0.0413267 0.0602278 0.01 0.0413267 0.0602278 -0.01 0.0348148 0.0559989 0.01 0.035925 0.0571091 0.01 0.0348148 0.0559989 -0.01 0.0371452 0.0580972 0.01 0.0371452 0.0580972 -0.01 0.035925 0.0571091 -0.01 0.0338267 0.0547787 -0.01 0.0338267 0.0547787 0.01 0.0329716 0.0534619 -0.01 0.0329716 0.0534619 0.01 0.0322588 0.052063 0.01 0.0322588 0.052063 -0.01 0.0316961 0.0505972 -0.01 0.0316961 0.0505972 0.01 0.0312897 0.0490806 -0.01 0.0312897 0.0490806 0.01 0.0310441 0.0475299 0.01 0.0310441 0.0475299 -0.01 0.065 -0.015 -0.01 0.065 -0.015 0.01 0.0634321 -0.0149178 0.01 0.08 9.41679e-18 0.01 0.08 9.41679e-18 -0.01 0.0799178 0.00156793 -0.01 0.0618813 -0.0146722 0.01 0.0634321 -0.0149178 -0.01 0.0603647 -0.0142658 0.01 0.0618813 -0.0146722 -0.01 0.0603647 -0.0142658 -0.01 0.0588989 -0.0137032 0.01 0.0575 -0.0129904 0.01 0.0588989 -0.0137032 -0.01 0.0561832 -0.0121353 0.01 0.0575 -0.0129904 -0.01 0.0561832 -0.0121353 -0.01 0.054963 -0.0111472 0.01 0.0538528 -0.010037 0.01 0.054963 -0.0111472 -0.01 0.0528647 -0.00881678 0.01 0.0538528 -0.010037 -0.01 0.0528647 -0.00881678 -0.01 0.0520096 -0.0075 0.01 0.0512968 -0.00610105 0.01 0.0520096 -0.0075 -0.01 0.0507342 -0.00463525 0.01 0.0512968 -0.00610105 -0.01 0.0507342 -0.00463525 -0.01 0.0503278 -0.00311868 0.01 0.0500822 -0.00156793 0.01 0.0503278 -0.00311868 -0.01 0.05 -1.60781e-17 0.01 0.0500822 -0.00156793 -0.01 0.05 -1.60781e-17 -0.01 0.0665679 -0.0149178 -0.01 0.0681187 -0.0146722 -0.01 0.0665679 -0.0149178 0.01 0.0681187 -0.0146722 0.01 0.0696353 -0.0142658 -0.01 0.0711011 -0.0137032 -0.01 0.0696353 -0.0142658 0.01 0.0725 -0.0129904 -0.01 0.0711011 -0.0137032 0.01 0.0725 -0.0129904 0.01 0.0738168 -0.0121353 -0.01 0.075037 -0.0111472 -0.01 0.0738168 -0.0121353 0.01 0.0761472 -0.010037 -0.01 0.075037 -0.0111472 0.01 0.0761472 -0.010037 0.01 0.0771353 -0.00881678 -0.01 0.0779904 -0.0075 -0.01 0.0771353 -0.00881678 0.01 0.0787032 -0.00610105 -0.01 0.0779904 -0.0075 0.01 0.0787032 -0.00610105 0.01 0.0792658 -0.00463525 -0.01 0.0796722 -0.00311868 -0.01 0.0792658 -0.00463525 0.01 0.0799178 -0.00156793 -0.01 0.0796722 -0.00311868 0.01 0.0799178 -0.00156793 0.01 0.0796722 0.00311868 0.01 0.0799178 0.00156793 0.01 0.0796722 0.00311868 -0.01 0.0779904 0.0075 0.01 0.0787032 0.00610105 0.01 0.0779904 0.0075 -0.01 0.0792658 0.00463525 0.01 0.0792658 0.00463525 -0.01 0.0787032 0.00610105 -0.01 0.0761472 0.010037 0.01 0.075037 0.0111472 -0.01 0.075037 0.0111472 0.01 0.0771353 0.00881678 -0.01 0.0761472 0.010037 -0.01 0.0771353 0.00881678 0.01 0.0711011 0.0137032 -0.01 0.0711011 0.0137032 0.01 0.0725 0.0129904 0.01 0.0725 0.0129904 -0.01 0.0738168 0.0121353 0.01 0.0738168 0.0121353 -0.01 0.0665679 0.0149178 0.01 0.0681187 0.0146722 0.01 0.0665679 0.0149178 -0.01 0.0696353 0.0142658 0.01 0.0696353 0.0142658 -0.01 0.0681187 0.0146722 -0.01 0.0634321 0.0149178 0.01 0.0618813 0.0146722 -0.01 0.0618813 0.0146722 0.01 0.065 0.015 -0.01 0.0634321 0.0149178 -0.01 0.065 0.015 0.01 0.0575 0.0129904 -0.01 0.0575 0.0129904 0.01 0.0588989 0.0137032 0.01 0.0588989 0.0137032 -0.01 0.0603647 0.0142658 0.01 0.0603647 0.0142658 -0.01 0.0538528 0.010037 0.01 0.054963 0.0111472 0.01 0.0538528 0.010037 -0.01 0.0561832 0.0121353 0.01 0.0561832 0.0121353 -0.01 0.054963 0.0111472 -0.01 0.0528647 0.00881678 -0.01 0.0528647 0.00881678 0.01 0.0520096 0.0075 -0.01 0.0520096 0.0075 0.01 0.0512968 0.00610105 0.01 0.0512968 0.00610105 -0.01 0.0507342 0.00463525 -0.01 0.0507342 0.00463525 0.01 0.0503278 0.00311868 -0.01 0.0503278 0.00311868 0.01 0.0500822 0.00156793 0.01 0.0500822 0.00156793 -0.01 0.0459619 -0.0609619 -0.01 0.0459619 -0.0609619 0.01 0.044394 -0.0608798 0.01 0.0609619 -0.0459619 0.01 0.0609619 -0.0459619 -0.01 0.0608798 -0.044394 -0.01 0.0428433 -0.0606342 0.01 0.044394 -0.0608798 -0.01 0.0413267 -0.0602278 0.01 0.0428433 -0.0606342 -0.01 0.0413267 -0.0602278 -0.01 0.0398609 -0.0596651 0.01 0.0384619 -0.0589523 0.01 0.0398609 -0.0596651 -0.01 0.0371452 -0.0580972 0.01 0.0384619 -0.0589523 -0.01 0.0371452 -0.0580972 -0.01 0.035925 -0.0571091 0.01 0.0348148 -0.0559989 0.01 0.035925 -0.0571091 -0.01 0.0338267 -0.0547787 0.01 0.0348148 -0.0559989 -0.01 0.0338267 -0.0547787 -0.01 0.0329716 -0.0534619 0.01 0.0322588 -0.052063 0.01 0.0329716 -0.0534619 -0.01 0.0316961 -0.0505972 0.01 0.0322588 -0.052063 -0.01 0.0316961 -0.0505972 -0.01 0.0312897 -0.0490806 0.01 0.0310441 -0.0475299 0.01 0.0312897 -0.0490806 -0.01 0.0309619 -0.0459619 0.01 0.0310441 -0.0475299 -0.01 0.0309619 -0.0459619 -0.01 0.0475299 -0.0608798 -0.01 0.0490806 -0.0606342 -0.01 0.0475299 -0.0608798 0.01 0.0490806 -0.0606342 0.01 0.0505972 -0.0602278 -0.01 0.052063 -0.0596651 -0.01 0.0505972 -0.0602278 0.01 0.0534619 -0.0589523 -0.01 0.052063 -0.0596651 0.01 0.0534619 -0.0589523 0.01 0.0547787 -0.0580972 -0.01 0.0559989 -0.0571091 -0.01 0.0547787 -0.0580972 0.01 0.0571091 -0.0559989 -0.01 0.0559989 -0.0571091 0.01 0.0571091 -0.0559989 0.01 0.0580972 -0.0547787 -0.01 0.0589523 -0.0534619 -0.01 0.0580972 -0.0547787 0.01 0.0596651 -0.052063 -0.01 0.0589523 -0.0534619 0.01 0.0596651 -0.052063 0.01 0.0602278 -0.0505972 -0.01 0.0606342 -0.0490806 -0.01 0.0602278 -0.0505972 0.01 0.0608798 -0.0475299 -0.01 0.0606342 -0.0490806 0.01 0.0608798 -0.0475299 0.01 0.0606342 -0.0428433 0.01 0.0608798 -0.044394 0.01 0.0606342 -0.0428433 -0.01 0.0589523 -0.0384619 0.01 0.0596651 -0.0398609 0.01 0.0589523 -0.0384619 -0.01 0.0602278 -0.0413267 0.01 0.0602278 -0.0413267 -0.01 0.0596651 -0.0398609 -0.01 0.0571091 -0.035925 0.01 0.0559989 -0.0348148 -0.01 0.0559989 -0.0348148 0.01 0.0580972 -0.0371452 -0.01 0.0571091 -0.035925 -0.01 0.0580972 -0.0371452 0.01 0.052063 -0.0322588 -0.01 0.052063 -0.0322588 0.01 0.0534619 -0.0329716 0.01 0.0534619 -0.0329716 -0.01 0.0547787 -0.0338267 0.01 0.0547787 -0.0338267 -0.01 0.0475299 -0.0310441 0.01 0.0490806 -0.0312897 0.01 0.0475299 -0.0310441 -0.01 0.0505972 -0.0316961 0.01 0.0505972 -0.0316961 -0.01 0.0490806 -0.0312897 -0.01 0.044394 -0.0310441 0.01 0.0428433 -0.0312897 -0.01 0.0428433 -0.0312897 0.01 0.0459619 -0.0309619 -0.01 0.044394 -0.0310441 -0.01 0.0459619 -0.0309619 0.01 0.0384619 -0.0329716 -0.01 0.0384619 -0.0329716 0.01 0.0398609 -0.0322588 0.01 0.0398609 -0.0322588 -0.01 0.0413267 -0.0316961 0.01 0.0413267 -0.0316961 -0.01 0.0348148 -0.035925 0.01 0.035925 -0.0348148 0.01 0.0348148 -0.035925 -0.01 0.0371452 -0.0338267 0.01 0.0371452 -0.0338267 -0.01 0.035925 -0.0348148 -0.01 0.0338267 -0.0371452 -0.01 0.0338267 -0.0371452 0.01 0.0329716 -0.0384619 -0.01 0.0329716 -0.0384619 0.01 0.0322588 -0.0398609 0.01 0.0322588 -0.0398609 -0.01 0.0316961 -0.0413267 -0.01 0.0316961 -0.0413267 0.01 0.0312897 -0.0428433 -0.01 0.0312897 -0.0428433 0.01 0.0310441 -0.044394 0.01 0.0310441 -0.044394 -0.01 1.60781e-17 -0.08 -0.01 1.60781e-17 -0.08 0.01 -0.00156793 -0.0799178 0.01 0.015 -0.065 0.01 0.015 -0.065 -0.01 0.0149178 -0.0634321 -0.01 -0.00311868 -0.0796722 0.01 -0.00156793 -0.0799178 -0.01 -0.00463525 -0.0792658 0.01 -0.00311868 -0.0796722 -0.01 -0.00463525 -0.0792658 -0.01 -0.00610105 -0.0787032 0.01 -0.0075 -0.0779904 0.01 -0.00610105 -0.0787032 -0.01 -0.00881678 -0.0771353 0.01 -0.0075 -0.0779904 -0.01 -0.00881678 -0.0771353 -0.01 -0.010037 -0.0761472 0.01 -0.0111472 -0.075037 0.01 -0.010037 -0.0761472 -0.01 -0.0121353 -0.0738168 0.01 -0.0111472 -0.075037 -0.01 -0.0121353 -0.0738168 -0.01 -0.0129904 -0.0725 0.01 -0.0137032 -0.0711011 0.01 -0.0129904 -0.0725 -0.01 -0.0142658 -0.0696353 0.01 -0.0137032 -0.0711011 -0.01 -0.0142658 -0.0696353 -0.01 -0.0146722 -0.0681187 0.01 -0.0149178 -0.0665679 0.01 -0.0146722 -0.0681187 -0.01 -0.015 -0.065 0.01 -0.0149178 -0.0665679 -0.01 -0.015 -0.065 -0.01 0.00156793 -0.0799178 -0.01 0.00311868 -0.0796722 -0.01 0.00156793 -0.0799178 0.01 0.00311868 -0.0796722 0.01 0.00463525 -0.0792658 -0.01 0.00610105 -0.0787032 -0.01 0.00463525 -0.0792658 0.01 0.0075 -0.0779904 -0.01 0.00610105 -0.0787032 0.01 0.0075 -0.0779904 0.01 0.00881678 -0.0771353 -0.01 0.010037 -0.0761472 -0.01 0.00881678 -0.0771353 0.01 0.0111472 -0.075037 -0.01 0.010037 -0.0761472 0.01 0.0111472 -0.075037 0.01 0.0121353 -0.0738168 -0.01 0.0129904 -0.0725 -0.01 0.0121353 -0.0738168 0.01 0.0137032 -0.0711011 -0.01 0.0129904 -0.0725 0.01 0.0137032 -0.0711011 0.01 0.0142658 -0.0696353 -0.01 0.0146722 -0.0681187 -0.01 0.0142658 -0.0696353 0.01 0.0149178 -0.0665679 -0.01 0.0146722 -0.0681187 0.01 0.0149178 -0.0665679 0.01 0.0146722 -0.0618813 0.01 0.0149178 -0.0634321 0.01 0.0146722 -0.0618813 -0.01 0.0129904 -0.0575 0.01 0.0137032 -0.0588989 0.01 0.0129904 -0.0575 -0.01 0.0142658 -0.0603647 0.01 0.0142658 -0.0603647 -0.01 0.0137032 -0.0588989 -0.01 0.0111472 -0.054963 0.01 0.010037 -0.0538528 -0.01 0.010037 -0.0538528 0.01 0.0121353 -0.0561832 -0.01 0.0111472 -0.054963 -0.01 0.0121353 -0.0561832 0.01 0.00610105 -0.0512968 -0.01 0.00610105 -0.0512968 0.01 0.0075 -0.0520096 0.01 0.0075 -0.0520096 -0.01 0.00881678 -0.0528647 0.01 0.00881678 -0.0528647 -0.01 0.00156793 -0.0500822 0.01 0.00311868 -0.0503278 0.01 0.00156793 -0.0500822 -0.01 0.00463525 -0.0507342 0.01 0.00463525 -0.0507342 -0.01 0.00311868 -0.0503278 -0.01 -0.00156793 -0.0500822 0.01 -0.00311868 -0.0503278 -0.01 -0.00311868 -0.0503278 0.01 -4.24915e-18 -0.05 -0.01 -0.00156793 -0.0500822 -0.01 -4.24915e-18 -0.05 0.01 -0.0075 -0.0520096 -0.01 -0.0075 -0.0520096 0.01 -0.00610105 -0.0512968 0.01 -0.00610105 -0.0512968 -0.01 -0.00463525 -0.0507342 0.01 -0.00463525 -0.0507342 -0.01 -0.0111472 -0.054963 0.01 -0.010037 -0.0538528 0.01 -0.0111472 -0.054963 -0.01 -0.00881678 -0.0528647 0.01 -0.00881678 -0.0528647 -0.01 -0.010037 -0.0538528 -0.01 -0.0121353 -0.0561832 -0.01 -0.0121353 -0.0561832 0.01 -0.0129904 -0.0575 -0.01 -0.0129904 -0.0575 0.01 -0.0137032 -0.0588989 0.01 -0.0137032 -0.0588989 -0.01 -0.0142658 -0.0603647 -0.01 -0.0142658 -0.0603647 0.01 -0.0146722 -0.0618813 -0.01 -0.0146722 -0.0618813 0.01 -0.0149178 -0.0634321 0.01 -0.0149178 -0.0634321 -0.01 -0.0459619 -0.0609619 -0.01 -0.0459619 -0.0609619 0.01 -0.0475299 -0.0608798 0.01 -0.0309619 -0.0459619 0.01 -0.0309619 -0.0459619 -0.01 -0.0310441 -0.044394 -0.01 -0.0490806 -0.0606342 0.01 -0.0475299 -0.0608798 -0.01 -0.0505972 -0.0602278 0.01 -0.0490806 -0.0606342 -0.01 -0.0505972 -0.0602278 -0.01 -0.052063 -0.0596651 0.01 -0.0534619 -0.0589523 0.01 -0.052063 -0.0596651 -0.01 -0.0547787 -0.0580972 0.01 -0.0534619 -0.0589523 -0.01 -0.0547787 -0.0580972 -0.01 -0.0559989 -0.0571091 0.01 -0.0571091 -0.0559989 0.01 -0.0559989 -0.0571091 -0.01 -0.0580972 -0.0547787 0.01 -0.0571091 -0.0559989 -0.01 -0.0580972 -0.0547787 -0.01 -0.0589523 -0.0534619 0.01 -0.0596651 -0.052063 0.01 -0.0589523 -0.0534619 -0.01 -0.0602278 -0.0505972 0.01 -0.0596651 -0.052063 -0.01 -0.0602278 -0.0505972 -0.01 -0.0606342 -0.0490806 0.01 -0.0608798 -0.0475299 0.01 -0.0606342 -0.0490806 -0.01 -0.0609619 -0.0459619 0.01 -0.0608798 -0.0475299 -0.01 -0.0609619 -0.0459619 -0.01 -0.044394 -0.0608798 -0.01 -0.0428433 -0.0606342 -0.01 -0.044394 -0.0608798 0.01 -0.0428433 -0.0606342 0.01 -0.0413267 -0.0602278 -0.01 -0.0398609 -0.0596651 -0.01 -0.0413267 -0.0602278 0.01 -0.0384619 -0.0589523 -0.01 -0.0398609 -0.0596651 0.01 -0.0384619 -0.0589523 0.01 -0.0371452 -0.0580972 -0.01 -0.035925 -0.0571091 -0.01 -0.0371452 -0.0580972 0.01 -0.0348148 -0.0559989 -0.01 -0.035925 -0.0571091 0.01 -0.0348148 -0.0559989 0.01 -0.0338267 -0.0547787 -0.01 -0.0329716 -0.0534619 -0.01 -0.0338267 -0.0547787 0.01 -0.0322588 -0.052063 -0.01 -0.0329716 -0.0534619 0.01 -0.0322588 -0.052063 0.01 -0.0316961 -0.0505972 -0.01 -0.0312897 -0.0490806 -0.01 -0.0316961 -0.0505972 0.01 -0.0310441 -0.0475299 -0.01 -0.0312897 -0.0490806 0.01 -0.0310441 -0.0475299 0.01 -0.0312897 -0.0428433 0.01 -0.0310441 -0.044394 0.01 -0.0312897 -0.0428433 -0.01 -0.0329716 -0.0384619 0.01 -0.0322588 -0.0398609 0.01 -0.0329716 -0.0384619 -0.01 -0.0316961 -0.0413267 0.01 -0.0316961 -0.0413267 -0.01 -0.0322588 -0.0398609 -0.01 -0.0348148 -0.035925 0.01 -0.035925 -0.0348148 -0.01 -0.035925 -0.0348148 0.01 -0.0338267 -0.0371452 -0.01 -0.0348148 -0.035925 -0.01 -0.0338267 -0.0371452 0.01 -0.0398609 -0.0322588 -0.01 -0.0398609 -0.0322588 0.01 -0.0384619 -0.0329716 0.01 -0.0384619 -0.0329716 -0.01 -0.0371452 -0.0338267 0.01 -0.0371452 -0.0338267 -0.01 -0.044394 -0.0310441 0.01 -0.0428433 -0.0312897 0.01 -0.044394 -0.0310441 -0.01 -0.0413267 -0.0316961 0.01 -0.0413267 -0.0316961 -0.01 -0.0428433 -0.0312897 -0.01 -0.0475299 -0.0310441 0.01 -0.0490806 -0.0312897 -0.01 -0.0490806 -0.0312897 0.01 -0.0459619 -0.0309619 -0.01 -0.0475299 -0.0310441 -0.01 -0.0459619 -0.0309619 0.01 -0.0534619 -0.0329716 -0.01 -0.0534619 -0.0329716 0.01 -0.052063 -0.0322588 0.01 -0.052063 -0.0322588 -0.01 -0.0505972 -0.0316961 0.01 -0.0505972 -0.0316961 -0.01 -0.0571091 -0.035925 0.01 -0.0559989 -0.0348148 0.01 -0.0571091 -0.035925 -0.01 -0.0547787 -0.0338267 0.01 -0.0547787 -0.0338267 -0.01 -0.0559989 -0.0348148 -0.01 -0.0580972 -0.0371452 -0.01 -0.0580972 -0.0371452 0.01 -0.0589523 -0.0384619 -0.01 -0.0589523 -0.0384619 0.01 -0.0596651 -0.0398609 0.01 -0.0596651 -0.0398609 -0.01 -0.0602278 -0.0413267 -0.01 -0.0602278 -0.0413267 0.01 -0.0606342 -0.0428433 -0.01 -0.0606342 -0.0428433 0.01 -0.0608798 -0.044394 0.01 -0.0608798 -0.044394 -0.01 -0.065 -0.015 -0.01 -0.065 -0.015 0.01 -0.0665679 -0.0149178 0.01 -0.05 9.41679e-18 0.01 -0.05 9.41679e-18 -0.01 -0.0500822 0.00156793 -0.01 -0.0681187 -0.0146722 0.01 -0.0665679 -0.0149178 -0.01 -0.0696353 -0.0142658 0.01 -0.0681187 -0.0146722 -0.01 -0.0696353 -0.0142658 -0.01 -0.0711011 -0.0137032 0.01 -0.0725 -0.0129904 0.01 -0.0711011 -0.0137032 -0.01 -0.0738168 -0.0121353 0.01 -0.0725 -0.0129904 -0.01 -0.0738168 -0.0121353 -0.01 -0.075037 -0.0111472 0.01 -0.0761472 -0.010037 0.01 -0.075037 -0.0111472 -0.01 -0.0771353 -0.00881678 0.01 -0.0761472 -0.010037 -0.01 -0.0771353 -0.00881678 -0.01 -0.0779904 -0.0075 0.01 -0.0787032 -0.00610105 0.01 -0.0779904 -0.0075 -0.01 -0.0792658 -0.00463525 0.01 -0.0787032 -0.00610105 -0.01 -0.0792658 -0.00463525 -0.01 -0.0796722 -0.00311868 0.01 -0.0799178 -0.00156793 0.01 -0.0796722 -0.00311868 -0.01 -0.08 -1.60781e-17 0.01 -0.0799178 -0.00156793 -0.01 -0.08 -1.60781e-17 -0.01 -0.0634321 -0.0149178 -0.01 -0.0618813 -0.0146722 -0.01 -0.0634321 -0.0149178 0.01 -0.0618813 -0.0146722 0.01 -0.0603647 -0.0142658 -0.01 -0.0588989 -0.0137032 -0.01 -0.0603647 -0.0142658 0.01 -0.0575 -0.0129904 -0.01 -0.0588989 -0.0137032 0.01 -0.0575 -0.0129904 0.01 -0.0561832 -0.0121353 -0.01 -0.054963 -0.0111472 -0.01 -0.0561832 -0.0121353 0.01 -0.0538528 -0.010037 -0.01 -0.054963 -0.0111472 0.01 -0.0538528 -0.010037 0.01 -0.0528647 -0.00881678 -0.01 -0.0520096 -0.0075 -0.01 -0.0528647 -0.00881678 0.01 -0.0512968 -0.00610105 -0.01 -0.0520096 -0.0075 0.01 -0.0512968 -0.00610105 0.01 -0.0507342 -0.00463525 -0.01 -0.0503278 -0.00311868 -0.01 -0.0507342 -0.00463525 0.01 -0.0500822 -0.00156793 -0.01 -0.0503278 -0.00311868 0.01 -0.0500822 -0.00156793 0.01 -0.0503278 0.00311868 0.01 -0.0500822 0.00156793 0.01 -0.0503278 0.00311868 -0.01 -0.0520096 0.0075 0.01 -0.0512968 0.00610105 0.01 -0.0520096 0.0075 -0.01 -0.0507342 0.00463525 0.01 -0.0507342 0.00463525 -0.01 -0.0512968 0.00610105 -0.01 -0.0538528 0.010037 0.01 -0.054963 0.0111472 -0.01 -0.054963 0.0111472 0.01 -0.0528647 0.00881678 -0.01 -0.0538528 0.010037 -0.01 -0.0528647 0.00881678 0.01 -0.0588989 0.0137032 -0.01 -0.0588989 0.0137032 0.01 -0.0575 0.0129904 0.01 -0.0575 0.0129904 -0.01 -0.0561832 0.0121353 0.01 -0.0561832 0.0121353 -0.01 -0.0634321 0.0149178 0.01 -0.0618813 0.0146722 0.01 -0.0634321 0.0149178 -0.01 -0.0603647 0.0142658 0.01 -0.0603647 0.0142658 -0.01 -0.0618813 0.0146722 -0.01 -0.0665679 0.0149178 0.01 -0.0681187 0.0146722 -0.01 -0.0681187 0.0146722 0.01 -0.065 0.015 -0.01 -0.0665679 0.0149178 -0.01 -0.065 0.015 0.01 -0.0725 0.0129904 -0.01 -0.0725 0.0129904 0.01 -0.0711011 0.0137032 0.01 -0.0711011 0.0137032 -0.01 -0.0696353 0.0142658 0.01 -0.0696353 0.0142658 -0.01 -0.0761472 0.010037 0.01 -0.075037 0.0111472 0.01 -0.0761472 0.010037 -0.01 -0.0738168 0.0121353 0.01 -0.0738168 0.0121353 -0.01 -0.075037 0.0111472 -0.01 -0.0771353 0.00881678 -0.01 -0.0771353 0.00881678 0.01 -0.0779904 0.0075 -0.01 -0.0779904 0.0075 0.01 -0.0787032 0.00610105 0.01 -0.0787032 0.00610105 -0.01 -0.0792658 0.00463525 -0.01 -0.0792658 0.00463525 0.01 -0.0796722 0.00311868 -0.01 -0.0796722 0.00311868 0.01 -0.0799178 0.00156793 0.01 -0.0799178 0.00156793 -0.01 -0.0459619 0.0309619 -0.01 -0.0459619 0.0309619 0.01 -0.0475299 0.0310441 0.01 -0.0309619 0.0459619 0.01 -0.0309619 0.0459619 -0.01 -0.0310441 0.0475299 -0.01 -0.0490806 0.0312897 0.01 -0.0475299 0.0310441 -0.01 -0.0505972 0.0316961 0.01 -0.0490806 0.0312897 -0.01 -0.0505972 0.0316961 -0.01 -0.052063 0.0322588 0.01 -0.0534619 0.0329716 0.01 -0.052063 0.0322588 -0.01 -0.0547787 0.0338267 0.01 -0.0534619 0.0329716 -0.01 -0.0547787 0.0338267 -0.01 -0.0559989 0.0348148 0.01 -0.0571091 0.035925 0.01 -0.0559989 0.0348148 -0.01 -0.0580972 0.0371452 0.01 -0.0571091 0.035925 -0.01 -0.0580972 0.0371452 -0.01 -0.0589523 0.0384619 0.01 -0.0596651 0.0398609 0.01 -0.0589523 0.0384619 -0.01 -0.0602278 0.0413267 0.01 -0.0596651 0.0398609 -0.01 -0.0602278 0.0413267 -0.01 -0.0606342 0.0428433 0.01 -0.0608798 0.044394 0.01 -0.0606342 0.0428433 -0.01 -0.0609619 0.0459619 0.01 -0.0608798 0.044394 -0.01 -0.0609619 0.0459619 -0.01 -0.044394 0.0310441 -0.01 -0.0428433 0.0312897 -0.01 -0.044394 0.0310441 0.01 -0.0428433 0.0312897 0.01 -0.0413267 0.0316961 -0.01 -0.0398609 0.0322588 -0.01 -0.0413267 0.0316961 0.01 -0.0384619 0.0329716 -0.01 -0.0398609 0.0322588 0.01 -0.0384619 0.0329716 0.01 -0.0371452 0.0338267 -0.01 -0.035925 0.0348148 -0.01 -0.0371452 0.0338267 0.01 -0.0348148 0.035925 -0.01 -0.035925 0.0348148 0.01 -0.0348148 0.035925 0.01 -0.0338267 0.0371452 -0.01 -0.0329716 0.0384619 -0.01 -0.0338267 0.0371452 0.01 -0.0322588 0.0398609 -0.01 -0.0329716 0.0384619 0.01 -0.0322588 0.0398609 0.01 -0.0316961 0.0413267 -0.01 -0.0312897 0.0428433 -0.01 -0.0316961 0.0413267 0.01 -0.0310441 0.044394 -0.01 -0.0312897 0.0428433 0.01 -0.0310441 0.044394 0.01 -0.0312897 0.0490806 0.01 -0.0310441 0.0475299 0.01 -0.0312897 0.0490806 -0.01 -0.0329716 0.0534619 0.01 -0.0322588 0.052063 0.01 -0.0329716 0.0534619 -0.01 -0.0316961 0.0505972 0.01 -0.0316961 0.0505972 -0.01 -0.0322588 0.052063 -0.01 -0.0348148 0.0559989 0.01 -0.035925 0.0571091 -0.01 -0.035925 0.0571091 0.01 -0.0338267 0.0547787 -0.01 -0.0348148 0.0559989 -0.01 -0.0338267 0.0547787 0.01 -0.0398609 0.0596651 -0.01 -0.0398609 0.0596651 0.01 -0.0384619 0.0589523 0.01 -0.0384619 0.0589523 -0.01 -0.0371452 0.0580972 0.01 -0.0371452 0.0580972 -0.01 -0.044394 0.0608798 0.01 -0.0428433 0.0606342 0.01 -0.044394 0.0608798 -0.01 -0.0413267 0.0602278 0.01 -0.0413267 0.0602278 -0.01 -0.0428433 0.0606342 -0.01 -0.0475299 0.0608798 0.01 -0.0490806 0.0606342 -0.01 -0.0490806 0.0606342 0.01 -0.0459619 0.0609619 -0.01 -0.0475299 0.0608798 -0.01 -0.0459619 0.0609619 0.01 -0.0534619 0.0589523 -0.01 -0.0534619 0.0589523 0.01 -0.052063 0.0596651 0.01 -0.052063 0.0596651 -0.01 -0.0505972 0.0602278 0.01 -0.0505972 0.0602278 -0.01 -0.0571091 0.0559989 0.01 -0.0559989 0.0571091 0.01 -0.0571091 0.0559989 -0.01 -0.0547787 0.0580972 0.01 -0.0547787 0.0580972 -0.01 -0.0559989 0.0571091 -0.01 -0.0580972 0.0547787 -0.01 -0.0580972 0.0547787 0.01 -0.0589523 0.0534619 -0.01 -0.0589523 0.0534619 0.01 -0.0596651 0.052063 0.01 -0.0596651 0.052063 -0.01 -0.0602278 0.0505972 -0.01 -0.0602278 0.0505972 0.01 -0.0606342 0.0490806 -0.01 -0.0606342 0.0490806 0.01 -0.0608798 0.0475299 0.01 -0.0608798 0.0475299 -0.01 -0.0042133 -0.109919 0.01 3.70592e-16 -0.11 0.01 3.97534e-16 -0.11 -0.01 0.11 2.02067e-17 0.01 0.109919 0.0042133 -0.01 0.11 2.02067e-17 -0.01 -0.0042133 -0.109919 -0.01 -0.00842042 -0.109677 0.01 -0.00842042 -0.109677 -0.01 -0.0126152 -0.109274 0.01 -0.0167914 -0.108711 0.01 -0.0126152 -0.109274 -0.01 -0.0167914 -0.108711 -0.01 -0.020943 -0.107988 0.01 -0.020943 -0.107988 -0.01 -0.0250639 -0.107106 0.01 -0.029148 -0.106068 0.01 -0.0250639 -0.107106 -0.01 -0.029148 -0.106068 -0.01 -0.0331893 -0.104874 0.01 -0.0331893 -0.104874 -0.01 -0.0371819 -0.103525 0.01 -0.0411199 -0.102025 0.01 -0.0371819 -0.103525 -0.01 -0.0411199 -0.102025 -0.01 -0.0449976 -0.100375 0.01 -0.0449976 -0.100375 -0.01 -0.0488092 -0.0985782 0.01 -0.0525492 -0.0966363 0.01 -0.0488092 -0.0985782 -0.01 -0.0525492 -0.0966363 -0.01 -0.0562121 -0.0945527 0.01 -0.0562121 -0.0945527 -0.01 -0.0597924 -0.0923302 0.01 -0.0632851 -0.0899722 0.01 -0.0597924 -0.0923302 -0.01 -0.0632851 -0.0899722 -0.01 -0.0666848 -0.0874822 0.01 -0.0666848 -0.0874822 -0.01 -0.0699867 -0.0848638 0.01 -0.0731858 -0.0821209 0.01 -0.0699867 -0.0848638 -0.01 -0.0731858 -0.0821209 -0.01 -0.0762776 -0.0792574 0.01 -0.0762776 -0.0792574 -0.01 -0.0792574 -0.0762776 0.01 -0.0821209 -0.0731858 0.01 -0.0792574 -0.0762776 -0.01 -0.0821209 -0.0731858 -0.01 -0.0848638 -0.0699867 0.01 -0.0848638 -0.0699867 -0.01 -0.0874822 -0.0666848 0.01 -0.0899722 -0.0632851 0.01 -0.0874822 -0.0666848 -0.01 -0.0899722 -0.0632851 -0.01 -0.0923302 -0.0597924 0.01 -0.0923302 -0.0597924 -0.01 -0.0945527 -0.0562121 0.01 -0.0966363 -0.0525492 0.01 -0.0945527 -0.0562121 -0.01 -0.0966363 -0.0525492 -0.01 -0.0985782 -0.0488092 0.01 -0.0985782 -0.0488092 -0.01 -0.100375 -0.0449976 0.01 -0.102025 -0.0411199 0.01 -0.100375 -0.0449976 -0.01 -0.102025 -0.0411199 -0.01 -0.103525 -0.0371819 0.01 -0.103525 -0.0371819 -0.01 -0.104874 -0.0331893 0.01 -0.106068 -0.029148 0.01 -0.104874 -0.0331893 -0.01 -0.106068 -0.029148 -0.01 -0.107106 -0.0250639 0.01 -0.107106 -0.0250639 -0.01 -0.107988 -0.020943 0.01 -0.108711 -0.0167914 0.01 -0.107988 -0.020943 -0.01 -0.108711 -0.0167914 -0.01 -0.109274 -0.0126152 0.01 -0.109274 -0.0126152 -0.01 -0.109677 -0.00842042 0.01 -0.109919 -0.0042133 0.01 -0.109677 -0.00842042 -0.01 -0.109919 -0.0042133 -0.01 -0.11 -2.02067e-17 0.01 -0.11 -2.02067e-17 -0.01 0.0042133 -0.109919 -0.01 0.0042133 -0.109919 0.01 0.00842042 -0.109677 -0.01 0.0126152 -0.109274 -0.01 0.00842042 -0.109677 0.01 0.0126152 -0.109274 0.01 0.0167914 -0.108711 -0.01 0.0167914 -0.108711 0.01 0.020943 -0.107988 -0.01 0.0250639 -0.107106 -0.01 0.020943 -0.107988 0.01 0.0250639 -0.107106 0.01 0.029148 -0.106068 -0.01 0.029148 -0.106068 0.01 0.0331893 -0.104874 -0.01 0.0371819 -0.103525 -0.01 0.0331893 -0.104874 0.01 0.0371819 -0.103525 0.01 0.0411199 -0.102025 -0.01 0.0411199 -0.102025 0.01 0.0449976 -0.100375 -0.01 0.0488092 -0.0985782 -0.01 0.0449976 -0.100375 0.01 0.0488092 -0.0985782 0.01 0.0525492 -0.0966363 -0.01 0.0525492 -0.0966363 0.01 0.0562121 -0.0945527 -0.01 0.0597924 -0.0923302 -0.01 0.0562121 -0.0945527 0.01 0.0597924 -0.0923302 0.01 0.0632851 -0.0899722 -0.01 0.0632851 -0.0899722 0.01 0.0666848 -0.0874822 -0.01 0.0699867 -0.0848638 -0.01 0.0666848 -0.0874822 0.01 0.0699867 -0.0848638 0.01 0.0731858 -0.0821209 -0.01 0.0731858 -0.0821209 0.01 0.0762776 -0.0792574 -0.01 0.0792574 -0.0762776 -0.01 0.0762776 -0.0792574 0.01 0.0792574 -0.0762776 0.01 0.0821209 -0.0731858 -0.01 0.0821209 -0.0731858 0.01 0.0848638 -0.0699867 -0.01 0.0874822 -0.0666848 -0.01 0.0848638 -0.0699867 0.01 0.0874822 -0.0666848 0.01 0.0899722 -0.0632851 -0.01 0.0899722 -0.0632851 0.01 0.0923302 -0.0597924 -0.01 0.0945527 -0.0562121 -0.01 0.0923302 -0.0597924 0.01 0.0945527 -0.0562121 0.01 0.0966363 -0.0525492 -0.01 0.0966363 -0.0525492 0.01 0.0985782 -0.0488092 -0.01 0.100375 -0.0449976 -0.01 0.0985782 -0.0488092 0.01 0.100375 -0.0449976 0.01 0.102025 -0.0411199 -0.01 0.102025 -0.0411199 0.01 0.103525 -0.0371819 -0.01 0.104874 -0.0331893 -0.01 0.103525 -0.0371819 0.01 0.104874 -0.0331893 0.01 0.106068 -0.029148 -0.01 0.106068 -0.029148 0.01 0.107106 -0.0250639 -0.01 0.107988 -0.020943 -0.01 0.107106 -0.0250639 0.01 0.107988 -0.020943 0.01 0.108711 -0.0167914 -0.01 0.108711 -0.0167914 0.01 0.109274 -0.0126152 -0.01 0.109677 -0.00842042 -0.01 0.109274 -0.0126152 0.01 0.109677 -0.00842042 0.01 0.109919 -0.0042133 -0.01 0.109919 -0.0042133 0.01 0.109677 0.00842042 0.01 0.109677 0.00842042 -0.01 0.109919 0.0042133 0.01 0.107988 0.020943 0.01 0.107988 0.020943 -0.01 0.108711 0.0167914 0.01 0.109274 0.0126152 0.01 0.108711 0.0167914 -0.01 0.109274 0.0126152 -0.01 0.106068 0.029148 0.01 0.104874 0.0331893 0.01 0.104874 0.0331893 -0.01 0.107106 0.0250639 -0.01 0.107106 0.0250639 0.01 0.106068 0.029148 -0.01 0.100375 0.0449976 -0.01 0.102025 0.0411199 0.01 0.100375 0.0449976 0.01 0.102025 0.0411199 -0.01 0.103525 0.0371819 -0.01 0.103525 0.0371819 0.01 0.0945527 0.0562121 0.01 0.0945527 0.0562121 -0.01 0.0966363 0.0525492 0.01 0.0985782 0.0488092 0.01 0.0966363 0.0525492 -0.01 0.0985782 0.0488092 -0.01 0.0899722 0.0632851 0.01 0.0874822 0.0666848 0.01 0.0874822 0.0666848 -0.01 0.0923302 0.0597924 -0.01 0.0923302 0.0597924 0.01 0.0899722 0.0632851 -0.01 0.0792574 0.0762776 -0.01 0.0821209 0.0731858 0.01 0.0792574 0.0762776 0.01 0.0821209 0.0731858 -0.01 0.0848638 0.0699867 -0.01 0.0848638 0.0699867 0.01 0.0699867 0.0848638 0.01 0.0699867 0.0848638 -0.01 0.0731858 0.0821209 0.01 0.0762776 0.0792574 0.01 0.0731858 0.0821209 -0.01 0.0762776 0.0792574 -0.01 0.0632851 0.0899722 0.01 0.0597924 0.0923302 0.01 0.0597924 0.0923302 -0.01 0.0666848 0.0874822 -0.01 0.0666848 0.0874822 0.01 0.0632851 0.0899722 -0.01 0.0488092 0.0985782 -0.01 0.0525492 0.0966363 0.01 0.0488092 0.0985782 0.01 0.0525492 0.0966363 -0.01 0.0562121 0.0945527 -0.01 0.0562121 0.0945527 0.01 0.0371819 0.103525 0.01 0.0371819 0.103525 -0.01 0.0411199 0.102025 0.01 0.0449976 0.100375 0.01 0.0411199 0.102025 -0.01 0.0449976 0.100375 -0.01 0.029148 0.106068 0.01 0.0250639 0.107106 0.01 0.0250639 0.107106 -0.01 0.0331893 0.104874 -0.01 0.0331893 0.104874 0.01 0.029148 0.106068 -0.01 0.0126152 0.109274 -0.01 0.0167914 0.108711 0.01 0.0126152 0.109274 0.01 0.0167914 0.108711 -0.01 0.020943 0.107988 -0.01 0.020943 0.107988 0.01 -9.09641e-17 0.11 0.01 -9.09641e-17 0.11 -0.01 0.0042133 0.109919 0.01 0.00842042 0.109677 0.01 0.0042133 0.109919 -0.01 0.00842042 0.109677 -0.01 -0.00842042 0.109677 0.01 -0.0126152 0.109274 0.01 -0.0126152 0.109274 -0.01 -0.0042133 0.109919 -0.01 -0.0042133 0.109919 0.01 -0.00842042 0.109677 -0.01 -0.0250639 0.107106 -0.01 -0.020943 0.107988 0.01 -0.0250639 0.107106 0.01 -0.020943 0.107988 -0.01 -0.0167914 0.108711 -0.01 -0.0167914 0.108711 0.01 -0.0371819 0.103525 0.01 -0.0371819 0.103525 -0.01 -0.0331893 0.104874 0.01 -0.029148 0.106068 0.01 -0.0331893 0.104874 -0.01 -0.029148 0.106068 -0.01 -0.0449976 0.100375 0.01 -0.0488092 0.0985782 0.01 -0.0488092 0.0985782 -0.01 -0.0411199 0.102025 -0.01 -0.0411199 0.102025 0.01 -0.0449976 0.100375 -0.01 -0.0597924 0.0923302 -0.01 -0.0562121 0.0945527 0.01 -0.0597924 0.0923302 0.01 -0.0562121 0.0945527 -0.01 -0.0525492 0.0966363 -0.01 -0.0525492 0.0966363 0.01 -0.0699867 0.0848638 0.01 -0.0699867 0.0848638 -0.01 -0.0666848 0.0874822 0.01 -0.0632851 0.0899722 0.01 -0.0666848 0.0874822 -0.01 -0.0632851 0.0899722 -0.01 -0.0762776 0.0792574 0.01 -0.0792574 0.0762776 0.01 -0.0792574 0.0762776 -0.01 -0.0731858 0.0821209 -0.01 -0.0731858 0.0821209 0.01 -0.0762776 0.0792574 -0.01 -0.0821209 0.0731858 0.01 -0.0821209 0.0731858 -0.01 -0.0848638 0.0699867 -0.01 -0.0848638 0.0699867 0.01 -0.0874822 0.0666848 0.01 -0.0874822 0.0666848 -0.01 -0.0899722 0.0632851 0.01 -0.0899722 0.0632851 -0.01 -0.0923302 0.0597924 -0.01 -0.0923302 0.0597924 0.01 -0.0945527 0.0562121 0.01 -0.0945527 0.0562121 -0.01 -0.0966363 0.0525492 0.01 -0.0966363 0.0525492 -0.01 -0.0985782 0.0488092 -0.01 -0.0985782 0.0488092 0.01 -0.100375 0.0449976 0.01 -0.100375 0.0449976 -0.01 -0.102025 0.0411199 0.01 -0.102025 0.0411199 -0.01 -0.103525 0.0371819 -0.01 -0.103525 0.0371819 0.01 -0.104874 0.0331893 0.01 -0.104874 0.0331893 -0.01 -0.106068 0.029148 0.01 -0.106068 0.029148 -0.01 -0.107106 0.0250639 -0.01 -0.107106 0.0250639 0.01 -0.107988 0.020943 0.01 -0.107988 0.020943 -0.01 -0.108711 0.0167914 0.01 -0.108711 0.0167914 -0.01 -0.109274 0.0126152 -0.01 -0.109274 0.0126152 0.01 -0.109677 0.00842042 0.01 -0.109677 0.00842042 -0.01 -0.109919 0.0042133 0.01 -0.109919 0.0042133 -0.01 -0.0848638 0.0699867 0.01 -0.0821209 0.0731858 0.01 -0.0589523 0.0534619 0.01 0.0309619 0.0459619 0.01 0.010037 0.0538528 0.01 0.0111472 0.054963 0.01 0.0488092 0.0985782 0.01 0.044394 0.0608798 0.01 0.0428433 0.0606342 0.01 0.0413267 0.0602278 0.01 0.0449976 0.100375 0.01 0.0525492 0.0966363 0.01 0.0562121 0.0945527 0.01 0.0459619 0.0609619 0.01 0.0490806 0.0606342 0.01 0.0597924 0.0923302 0.01 0.0632851 0.0899722 0.01 0.0310441 0.0475299 0.01 0.0121353 0.0561832 0.01 0.00881678 0.0528647 0.01 0.0310441 0.044394 0.01 0.0411199 0.102025 0.01 0.0137032 0.0711011 0.01 0.0666848 0.0874822 0.01 0.052063 0.0596651 0.01 0.0505972 0.0602278 0.01 0.0398609 0.0596651 0.01 0.0142658 0.0696353 0.01 0.0731858 0.0821209 0.01 0.0547787 0.0580972 0.01 0.0534619 0.0589523 0.01 0.0146722 0.0618813 0.01 0.0329716 0.0534619 0.01 0.0142658 0.0603647 0.01 0.0312897 0.0428433 0.01 0.015 0.065 0.01 0.035925 0.0571091 0.01 0.0348148 0.0559989 0.01 0.0792574 0.0762776 0.01 0.0559989 0.0571091 0.01 0.0762776 0.0792574 0.01 0.0149178 0.0665679 0.01 0.0371452 0.0580972 0.01 0.0821209 0.0731858 0.01 0.0580972 0.0547787 0.01 0.0129904 0.0725 0.01 0.0316961 0.0413267 0.01 0.0075 0.0520096 0.01 0.0121353 0.0738168 0.01 0.0371819 0.103525 0.01 0.0874822 0.0666848 0.01 0.0596651 0.052063 0.01 0.0848638 0.0699867 0.01 0.0111472 0.075037 0.01 0.029148 0.106068 0.01 0.0331893 0.104874 0.01 0.0899722 0.0632851 0.01 0.0606342 0.0490806 0.01 0.0602278 0.0505972 0.01 0.0250639 0.107106 0.01 0.010037 0.0761472 0.01 0.0608798 0.0475299 0.01 0.0923302 0.0597924 0.01 0.0945527 0.0562121 0.01 0.020943 0.107988 0.01 0.00881678 0.0771353 0.01 0.0075 0.0779904 0.01 0.00610105 0.0512968 0.01 0.0167914 0.108711 0.01 0.00610105 0.0787032 0.01 0.0126152 0.109274 0.01 0.0966363 0.0525492 0.01 0.0609619 0.0459619 0.01 0.00463525 0.0792658 0.01 0.00311868 0.0796722 0.01 0.00842042 0.109677 0.01 0.0608798 0.044394 0.01 0.00156793 0.0799178 0.01 -9.09641e-17 0.11 0.01 0.0042133 0.109919 0.01 0.0985782 0.0488092 0.01 -0.00156793 0.0799178 0.01 -0.0042133 0.109919 0.01 -4.24915e-18 0.08 0.01 0.0322588 0.0398609 0.01 -0.00842042 0.109677 0.01 -0.00311868 0.0796722 0.01 -0.00463525 0.0792658 0.01 0.00463525 0.0507342 0.01 0.0329716 0.0384619 0.01 -0.0167914 0.108711 0.01 -0.00610105 0.0787032 0.01 -0.0075 0.0779904 0.01 0.0606342 0.0428433 0.01 0.100375 0.0449976 0.01 0.0602278 0.0413267 0.01 -0.020943 0.107988 0.01 -0.00881678 0.0771353 0.01 -0.0250639 0.107106 0.01 0.00311868 0.0503278 0.01 -0.029148 0.106068 0.01 -0.010037 0.0761472 0.01 0.0665679 0.0149178 0.01 0.065 0.015 0.01 0.0571091 0.035925 0.01 -0.0129904 0.0725 0.01 -0.0371819 0.103525 0.01 -0.0121353 0.0738168 0.01 0.0559989 0.0348148 0.01 0.0634321 0.0149178 0.01 0.0547787 0.0338267 0.01 -0.0699867 0.0848638 0.01 -0.0534619 0.0589523 0.01 -0.0731858 0.0821209 0.01 -0.0899722 0.0632851 0.01 -0.0606342 0.0490806 0.01 -0.0923302 0.0597924 0.01 0.102025 0.0411199 0.01 0.0711011 0.0137032 0.01 0.0588989 0.0137032 0.01 0.0505972 0.0316961 0.01 0.052063 0.0322588 0.01 -0.102025 0.0411199 0.01 -0.0725 0.0129904 0.01 -0.103525 0.0371819 0.01 0.0771353 0.00881678 0.01 0.107106 0.0250639 0.01 0.107988 0.020943 0.01 -0.0771353 0.00881678 0.01 -0.0779904 0.0075 0.01 -0.107988 0.020943 0.01 0.054963 0.0111472 0.01 0.0538528 0.010037 0.01 0.0459619 0.0309619 0.01 -0.0796722 0.00311868 0.01 -0.0799178 0.00156793 0.01 -0.109919 0.0042133 0.01 0.0528647 0.00881678 0.01 0.044394 0.0310441 0.01 -0.0725 -0.0129904 0.01 -0.0711011 -0.0137032 0.01 -0.102025 -0.0411199 0.01 0.0799178 -0.00156793 0.01 0.08 9.41679e-18 0.01 0.109919 -0.0042133 0.01 0.0796722 -0.00311868 0.01 0.109677 -0.00842042 0.01 0.0512968 0.00610105 0.01 0.0507342 0.00463525 0.01 0.0398609 0.0322588 0.01 -0.052063 -0.0322588 0.01 -0.0603647 -0.0142658 0.01 -0.0588989 -0.0137032 0.01 0.107988 -0.020943 0.01 0.0771353 -0.00881678 0.01 0.0779904 -0.0075 0.01 -0.0602278 -0.0505972 0.01 -0.0899722 -0.0632851 0.01 -0.0606342 -0.0490806 0.01 0.075037 -0.0111472 0.01 0.0761472 -0.010037 0.01 0.106068 -0.029148 0.01 -0.0547787 -0.0580972 0.01 -0.0762776 -0.0792574 0.01 -0.0559989 -0.0571091 0.01 0.103525 -0.0371819 0.01 0.0738168 -0.0121353 0.01 0.104874 -0.0331893 0.01 -0.0597924 -0.0923302 0.01 -0.0632851 -0.0899722 0.01 -0.0490806 -0.0606342 0.01 0.0348148 -0.035925 0.01 0.00156793 -0.0500822 0.01 -4.24915e-18 -0.05 0.01 0.0966363 -0.0525492 0.01 0.0945527 -0.0562121 0.01 0.0609619 -0.0459619 0.01 -0.0371819 -0.103525 0.01 -0.0121353 -0.0738168 0.01 -0.0331893 -0.104874 0.01 0.0602278 -0.0505972 0.01 0.0606342 -0.0490806 0.01 0.0899722 -0.0632851 0.01 -0.020943 -0.107988 0.01 -0.00881678 -0.0771353 0.01 -0.0075 -0.0779904 0.01 0.0538528 -0.010037 0.01 0.044394 -0.0310441 0.01 0.0528647 -0.00881678 0.01 0.00311868 -0.0796722 0.01 0.0042133 -0.109919 0.01 0.00156793 -0.0799178 0.01 0.0547787 -0.0580972 0.01 0.0731858 -0.0821209 0.01 0.0534619 -0.0589523 0.01 0.0322588 -0.0398609 0.01 0.0316961 -0.0413267 0.01 0.00610105 -0.0512968 0.01 0.0632851 -0.0899722 0.01 0.0490806 -0.0606342 0.01 0.0505972 -0.0602278 0.01 0.0398609 -0.0596651 0.01 0.0137032 -0.0711011 0.01 0.0142658 -0.0696353 0.01 0.0459619 -0.0609619 0.01 0.0525492 -0.0966363 0.01 0.044394 -0.0608798 0.01 0.0475299 -0.0608798 0.01 0.0597924 -0.0923302 0.01 0.035925 -0.0348148 0.01 0.0500822 -0.00156793 0.01 0.0371452 -0.0338267 0.01 0.0149178 -0.0665679 0.01 0.035925 -0.0571091 0.01 0.0371452 -0.0580972 0.01 0.0146722 -0.0681187 0.01 0.0762776 -0.0792574 0.01 0.0559989 -0.0571091 0.01 0.0792574 -0.0762776 0.01 0.0666848 -0.0874822 0.01 0.0129904 -0.0725 0.01 0.0411199 -0.102025 0.01 0.015 -0.065 0.01 0.0348148 -0.0559989 0.01 0.0413267 -0.0316961 0.01 0.0520096 -0.0075 0.01 0.0428433 -0.0312897 0.01 0.0580972 -0.0547787 0.01 0.0821209 -0.0731858 0.01 0.00463525 -0.0792658 0.01 0.0126152 -0.109274 0.01 0.00842042 -0.109677 0.01 0.029148 -0.106068 0.01 0.0111472 -0.075037 0.01 0.0331893 -0.104874 0.01 0.0923302 -0.0597924 0.01 0.0561832 -0.0121353 0.01 0.0475299 -0.0310441 0.01 0.054963 -0.0111472 0.01 -0.00610105 -0.0787032 0.01 -0.00463525 -0.0792658 0.01 -0.0126152 -0.109274 0.01 0.00463525 -0.0507342 0.01 0.0608798 -0.0475299 0.01 0.0634321 -0.0149178 0.01 0.0547787 -0.0338267 0.01 0.0618813 -0.0146722 0.01 -0.0111472 -0.075037 0.01 -0.029148 -0.106068 0.01 -0.010037 -0.0761472 0.01 -0.0250639 -0.107106 0.01 0.035925 0.0348148 0.01 0.0500822 0.00156793 0.01 0.05 -1.60781e-17 0.01 0.102025 -0.0411199 0.01 0.100375 -0.0449976 0.01 0.0602278 -0.0413267 0.01 -0.0398609 -0.0596651 0.01 -0.0384619 -0.0589523 0.01 -0.0142658 -0.0696353 0.01 0.0725 -0.0129904 0.01 -0.0371452 -0.0580972 0.01 -0.035925 -0.0571091 0.01 -0.0149178 -0.0665679 0.01 -0.0137032 -0.0588989 0.01 -0.0142658 -0.0603647 0.01 -0.0322588 -0.052063 0.01 0.0371452 0.0338267 0.01 0.0503278 0.00311868 0.01 -0.0459619 -0.0609619 0.01 -0.0525492 -0.0966363 0.01 -0.0562121 -0.0945527 0.01 -0.052063 -0.0596651 0.01 -0.0666848 -0.0874822 0.01 -0.0699867 -0.0848638 0.01 0.0384619 0.0329716 0.01 0.107106 -0.0250639 0.01 -0.0731858 -0.0821209 0.01 -0.0534619 -0.0589523 0.01 -0.0821209 -0.0731858 0.01 -0.0580972 -0.0547787 0.01 -0.0792574 -0.0762776 0.01 0.108711 -0.0167914 0.01 0.0787032 -0.00610105 0.01 -0.0111472 -0.054963 0.01 -0.0309619 -0.0459619 0.01 -0.010037 -0.0538528 0.01 -0.0608798 -0.0475299 0.01 -0.0945527 -0.0562121 0.01 -0.0609619 -0.0459619 0.01 0.0413267 0.0316961 0.01 -0.065 -0.015 0.01 -0.0571091 -0.035925 0.01 -0.0665679 -0.0149178 0.01 -0.0538528 -0.010037 0.01 -0.0459619 -0.0309619 0.01 -0.054963 -0.0111472 0.01 0.0428433 0.0312897 0.01 0.0520096 0.0075 0.01 -0.0475299 -0.0310441 0.01 -0.0561832 -0.0121353 0.01 -0.104874 -0.0331893 0.01 -0.075037 -0.0111472 0.01 -0.0738168 -0.0121353 0.01 -0.106068 -0.029148 0.01 -0.107106 -0.0250639 0.01 -0.0761472 -0.010037 0.01 -0.109919 -0.0042133 0.01 -0.0796722 -0.00311868 0.01 -0.109677 -0.00842042 0.01 0.11 2.02067e-17 0.01 0.109919 0.0042133 0.01 0.0799178 0.00156793 0.01 -0.0459619 0.0309619 0.01 -0.0538528 0.010037 0.01 -0.054963 0.0111472 0.01 -0.075037 0.0111472 0.01 -0.106068 0.029148 0.01 -0.104874 0.0331893 0.01 0.0792658 0.00463525 0.01 0.109677 0.00842042 0.01 0.0796722 0.00311868 0.01 0.108711 0.0167914 0.01 0.0787032 0.00610105 0.01 0.0779904 0.0075 0.01 -0.0561832 0.0121353 0.01 -0.0475299 0.0310441 0.01 -0.065 0.015 0.01 -0.0559989 0.0348148 0.01 -0.0634321 0.0149178 0.01 0.0348148 0.035925 0.01 1.60781e-17 0.05 0.01 0.00156793 0.0500822 0.01 0.0575 0.0129904 0.01 0.0561832 0.0121353 0.01 0.0490806 0.0312897 0.01 -0.0571091 0.035925 0.01 -0.0665679 0.0149178 0.01 -0.0580972 0.0371452 0.01 -0.0490806 0.0312897 0.01 -0.0575 0.0129904 0.01 0.075037 0.0111472 0.01 0.106068 0.029148 0.01 0.0761472 0.010037 0.01 0.103525 0.0371819 0.01 0.0738168 0.0121353 0.01 0.0725 0.0129904 0.01 -0.0608798 0.0475299 0.01 -0.0945527 0.0562121 0.01 -0.0398609 0.0596651 0.01 -0.0413267 0.0602278 0.01 -0.0137032 0.0711011 0.01 0.0338267 0.0371452 0.01 0.0618813 0.0146722 0.01 0.0603647 0.0142658 0.01 0.0534619 0.0329716 0.01 -0.0874822 0.0666848 0.01 -0.0596651 0.052063 0.01 0.0681187 0.0146722 0.01 0.0580972 0.0371452 0.01 -0.0762776 0.0792574 0.01 -0.0547787 0.0580972 0.01 -0.0559989 0.0571091 0.01 -0.0459619 0.0609619 0.01 -0.0525492 0.0966363 0.01 -0.044394 0.0608798 0.01 0.0589523 0.0384619 0.01 -0.0411199 0.102025 0.01 -0.0331893 0.104874 0.01 -0.0111472 0.075037 0.01 0.0696353 0.0142658 0.01 0.0596651 0.0398609 0.01 0.0596651 -0.0398609 0.01 0.0589523 -0.0384619 0.01 0.0696353 -0.0142658 0.01 0.0603647 -0.0142658 0.01 0.0534619 -0.0329716 0.01 0.052063 -0.0322588 0.01 0.0848638 -0.0699867 0.01 0.0589523 -0.0534619 0.01 0.0596651 -0.052063 0.01 0.0507342 -0.00463525 0.01 0.0398609 -0.0322588 0.01 0.0384619 -0.0329716 0.01 0.0384619 -0.0589523 0.01 0.0413267 -0.0602278 0.01 0.00881678 -0.0771353 0.01 0.0250639 -0.107106 0.01 0.020943 -0.107988 0.01 0.0329716 -0.0384619 0.01 0.00311868 -0.0503278 0.01 -0.0411199 -0.102025 0.01 -0.0137032 -0.0711011 0.01 -0.0129904 -0.0725 0.01 -0.0129904 -0.0575 0.01 -0.0316961 -0.0505972 0.01 -0.0505972 -0.0602278 0.01 -0.0589523 -0.0534619 0.01 -0.0848638 -0.0699867 0.01 -0.0596651 -0.052063 0.01 -0.0634321 -0.0149178 0.01 -0.0618813 -0.0146722 0.01 -0.0547787 -0.0338267 0.01 -0.0505972 -0.0316961 0.01 -0.044394 -0.0310441 0.01 -0.0528647 -0.00881678 0.01 -0.109677 0.00842042 0.01 -0.109274 0.0126152 0.01 -0.0792658 0.00463525 0.01 -0.0761472 0.010037 0.01 -0.107106 0.0250639 0.01 -0.0738168 0.0121353 0.01 -0.0711011 0.0137032 0.01 -0.0596651 0.0398609 0.01 -0.0696353 0.0142658 0.01 -0.0588989 0.0137032 0.01 -0.0603647 0.0142658 0.01 -0.052063 0.0322588 0.01 -0.0371452 0.0580972 0.01 -0.0384619 0.0589523 0.01 -0.0146722 0.0681187 0.01 -0.0602278 0.0505972 0.01 -0.0449976 0.100375 0.01 -0.0792574 0.0762776 0.01 -0.0580972 0.0547787 0.01 -0.052063 0.0596651 0.01 -0.0666848 0.0874822 0.01 -0.0632851 0.0899722 0.01 -0.0505972 0.0602278 0.01 -0.0475299 0.0608798 0.01 -0.0562121 0.0945527 0.01 -0.0488092 0.0985782 0.01 -0.0428433 0.0606342 0.01 -0.0126152 0.109274 0.01 0.0384619 0.0589523 0.01 0.0149178 0.0634321 0.01 0.0146722 0.0681187 0.01 0.0338267 0.0547787 0.01 0.0322588 0.052063 0.01 0.0137032 0.0588989 0.01 0.0316961 0.0505972 0.01 0.0129904 0.0575 0.01 0.109274 -0.0126152 0.01 0.0792658 -0.00463525 0.01 3.70592e-16 -0.11 0.01 -0.0042133 -0.109919 0.01 -0.00156793 -0.0799178 0.01 -0.00311868 -0.0796722 0.01 -0.00842042 -0.109677 0.01 0.0711011 -0.0137032 0.01 0.0571091 -0.035925 0.01 0.0665679 -0.0149178 0.01 0.0580972 -0.0371452 0.01 0.065 -0.015 0.01 0.0559989 -0.0348148 0.01 0.0428433 -0.0606342 0.01 0.0449976 -0.100375 0.01 0.0874822 -0.0666848 0.01 0.0512968 -0.00610105 0.01 0.0488092 -0.0985782 0.01 0.052063 -0.0596651 0.01 0.0699867 -0.0848638 0.01 0.0503278 -0.00311868 0.01 0.0562121 -0.0945527 0.01 0.0312897 0.0490806 0.01 0.0475299 0.0608798 0.01 0.0699867 0.0848638 0.01 0.0571091 0.0559989 0.01 0.0589523 0.0534619 0.01 0.0681187 -0.0146722 0.01 0.0606342 -0.0428433 0.01 0.0985782 -0.0488092 0.01 0.0608798 -0.044394 0.01 0.0575 -0.0129904 0.01 0.0588989 -0.0137032 0.01 0.0505972 -0.0316961 0.01 -0.035925 0.0348148 0.01 -0.0316961 -0.0413267 0.01 -0.00610105 -0.0512968 0.01 -0.0075 -0.0520096 0.01 0.0142658 -0.0603647 0.01 0.0322588 -0.052063 0.01 0.0329716 -0.0534619 0.01 0.0149178 -0.0634321 0.01 0.0146722 -0.0618813 0.01 0.0338267 -0.0547787 0.01 0.0121353 -0.0738168 0.01 0.0167914 -0.108711 0.01 0.0075 -0.0779904 0.01 0.0312897 -0.0490806 0.01 0.0121353 -0.0561832 0.01 0.0310441 -0.0475299 0.01 0.0137032 -0.0588989 0.01 0.0129904 -0.0575 0.01 0.0316961 -0.0505972 0.01 -0.0923302 -0.0597924 0.01 -0.0384619 -0.0329716 0.01 -0.0398609 -0.0322588 0.01 -0.0507342 -0.00463525 0.01 -0.0413267 -0.0602278 0.01 0.0475299 0.0310441 0.01 0.104874 0.0331893 0.01 0.109274 0.0126152 0.01 0.0571091 -0.0559989 0.01 0.0371819 -0.103525 0.01 0.010037 -0.0761472 0.01 0.00610105 -0.0787032 0.01 0.010037 -0.0538528 0.01 0.0309619 -0.0459619 0.01 0.0111472 -0.054963 0.01 -0.0348148 0.035925 0.01 -0.00156793 0.0500822 0.01 -0.0167914 -0.108711 0.01 0.0338267 -0.0371452 0.01 -0.0329716 -0.0534619 0.01 -0.0146722 -0.0618813 0.01 -0.0348148 -0.0559989 0.01 -0.0149178 -0.0634321 0.01 -0.015 -0.065 0.01 -0.044394 -0.0608798 0.01 -0.0488092 -0.0985782 0.01 -0.0428433 -0.0606342 0.01 -0.0449976 -0.100375 0.01 -0.0608798 -0.044394 0.01 -0.0966363 -0.0525492 0.01 -0.0792658 -0.00463525 0.01 -0.109274 -0.0126152 0.01 -0.100375 -0.0449976 0.01 -0.0602278 -0.0413267 0.01 -0.0606342 -0.0428433 0.01 0.0459619 -0.0309619 0.01 0.0490806 -0.0312897 0.01 0.0075 -0.0520096 0.01 0.0312897 -0.0428433 0.01 0.00881678 -0.0528647 0.01 1.60781e-17 -0.08 0.01 -0.0146722 -0.0681187 0.01 -0.0338267 -0.0547787 0.01 -0.0312897 -0.0490806 0.01 -0.0121353 -0.0561832 0.01 -0.0475299 -0.0608798 0.01 -0.0310441 -0.0475299 0.01 -0.0571091 -0.0559989 0.01 -0.0874822 -0.0666848 0.01 -0.0580972 -0.0371452 0.01 -0.0596651 -0.0398609 0.01 -0.0696353 -0.0142658 0.01 -0.0589523 -0.0384619 0.01 -0.0322588 -0.0398609 0.01 -0.0329716 -0.0384619 0.01 -0.00463525 -0.0507342 0.01 -0.0348148 -0.035925 0.01 -0.00156793 -0.0500822 0.01 -0.0338267 -0.0371452 0.01 -0.0428433 -0.0312897 0.01 -0.0520096 -0.0075 0.01 -0.0413267 -0.0316961 0.01 -0.05 9.41679e-18 0.01 -0.035925 -0.0348148 0.01 -0.0500822 -0.00156793 0.01 -0.0799178 -0.00156793 0.01 -0.11 -2.02067e-17 0.01 -0.08 -1.60781e-17 0.01 -0.00311868 0.0503278 0.01 -0.0338267 0.0371452 0.01 -0.0329716 0.0384619 0.01 -0.108711 0.0167914 0.01 -0.0787032 0.00610105 0.01 -0.0503278 -0.00311868 0.01 -0.0371452 -0.0338267 0.01 -0.010037 0.0538528 0.01 -0.0309619 0.0459619 0.01 -0.0111472 0.054963 0.01 0.0310441 -0.044394 0.01 -0.0310441 -0.044394 0.01 -0.0312897 -0.0428433 0.01 -0.00881678 -0.0528647 0.01 -0.0985782 -0.0488092 0.01 -0.0681187 -0.0146722 0.01 -0.0559989 -0.0348148 0.01 -0.0490806 -0.0312897 0.01 -0.103525 -0.0371819 0.01 -0.0787032 -0.00610105 0.01 -0.108711 -0.0167914 0.01 -0.0779904 -0.0075 0.01 -0.107988 -0.020943 0.01 -0.0771353 -0.00881678 0.01 -0.0512968 -0.00610105 0.01 -0.0512968 0.00610105 0.01 -0.0413267 0.0316961 0.01 -0.0398609 0.0322588 0.01 -0.0520096 0.0075 0.01 -0.0428433 0.0312897 0.01 -0.0500822 0.00156793 0.01 -0.0503278 0.00311868 0.01 -0.0371452 0.0338267 0.01 -0.0312897 0.0428433 0.01 -0.0310441 0.044394 0.01 -0.00881678 0.0528647 0.01 -0.0316961 0.0413267 0.01 -0.00610105 0.0512968 0.01 -0.0322588 0.0398609 0.01 -0.00311868 -0.0503278 0.01 -0.0528647 0.00881678 0.01 -0.044394 0.0310441 0.01 -0.0575 -0.0129904 0.01 -0.0534619 -0.0329716 0.01 -0.0681187 0.0146722 0.01 -0.0618813 0.0146722 0.01 -0.0534619 0.0329716 0.01 -0.0505972 0.0316961 0.01 -0.0985782 0.0488092 0.01 -0.0608798 0.044394 0.01 -0.0606342 0.0428433 0.01 -0.0602278 0.0413267 0.01 -0.100375 0.0449976 0.01 -0.0966363 0.0525492 0.01 -0.0329716 0.0534619 0.01 -0.0142658 0.0603647 0.01 -0.0322588 0.052063 0.01 -0.0338267 0.0547787 0.01 -0.0149178 0.0634321 0.01 -0.0146722 0.0618813 0.01 -0.0316961 0.0505972 0.01 -0.0137032 0.0588989 0.01 -0.0129904 0.0575 0.01 -0.0310441 0.0475299 0.01 -0.0312897 0.0490806 0.01 -0.0121353 0.0561832 0.01 -0.0507342 0.00463525 0.01 -0.0384619 0.0329716 0.01 -0.0075 0.0520096 0.01 -0.00463525 0.0507342 0.01 -0.0348148 0.0559989 0.01 -0.035925 0.0571091 0.01 -0.015 0.065 0.01 -0.0609619 0.0459619 0.01 -0.0589523 0.0384619 0.01 -0.0547787 0.0338267 0.01 -0.0571091 0.0559989 0.01 -0.0142658 0.0696353 0.01 -0.0490806 0.0606342 0.01 -0.0597924 0.0923302 0.01 -0.0149178 0.0665679 0.01 -0.0848638 0.0699867 -0.01 -0.0589523 0.0534619 -0.01 -0.0821209 0.0731858 -0.01 0.0309619 0.0459619 -0.01 0.0111472 0.054963 -0.01 0.010037 0.0538528 -0.01 0.0488092 0.0985782 -0.01 0.0428433 0.0606342 -0.01 0.044394 0.0608798 -0.01 0.0449976 0.100375 -0.01 0.0413267 0.0602278 -0.01 0.0525492 0.0966363 -0.01 0.0459619 0.0609619 -0.01 0.0562121 0.0945527 -0.01 0.0490806 0.0606342 -0.01 0.0632851 0.0899722 -0.01 0.0597924 0.0923302 -0.01 0.0310441 0.0475299 -0.01 0.0121353 0.0561832 -0.01 0.00881678 0.0528647 -0.01 0.0310441 0.044394 -0.01 0.0411199 0.102025 -0.01 0.0137032 0.0711011 -0.01 0.0666848 0.0874822 -0.01 0.0505972 0.0602278 -0.01 0.052063 0.0596651 -0.01 0.0398609 0.0596651 -0.01 0.0142658 0.0696353 -0.01 0.0731858 0.0821209 -0.01 0.0534619 0.0589523 -0.01 0.0547787 0.0580972 -0.01 0.0146722 0.0618813 -0.01 0.0142658 0.0603647 -0.01 0.0329716 0.0534619 -0.01 0.0312897 0.0428433 -0.01 0.015 0.065 -0.01 0.0348148 0.0559989 -0.01 0.035925 0.0571091 -0.01 0.0792574 0.0762776 -0.01 0.0762776 0.0792574 -0.01 0.0559989 0.0571091 -0.01 0.0149178 0.0665679 -0.01 0.0371452 0.0580972 -0.01 0.0580972 0.0547787 -0.01 0.0821209 0.0731858 -0.01 0.0129904 0.0725 -0.01 0.0316961 0.0413267 -0.01 0.0075 0.0520096 -0.01 0.0371819 0.103525 -0.01 0.0121353 0.0738168 -0.01 0.0874822 0.0666848 -0.01 0.0848638 0.0699867 -0.01 0.0596651 0.052063 -0.01 0.0111472 0.075037 -0.01 0.0331893 0.104874 -0.01 0.029148 0.106068 -0.01 0.0899722 0.0632851 -0.01 0.0602278 0.0505972 -0.01 0.0606342 0.0490806 -0.01 0.0250639 0.107106 -0.01 0.010037 0.0761472 -0.01 0.0608798 0.0475299 -0.01 0.0945527 0.0562121 -0.01 0.0923302 0.0597924 -0.01 0.020943 0.107988 -0.01 0.0075 0.0779904 -0.01 0.00881678 0.0771353 -0.01 0.00610105 0.0512968 -0.01 0.0167914 0.108711 -0.01 0.0126152 0.109274 -0.01 0.00610105 0.0787032 -0.01 0.0609619 0.0459619 -0.01 0.0966363 0.0525492 -0.01 0.00463525 0.0792658 -0.01 0.00842042 0.109677 -0.01 0.00311868 0.0796722 -0.01 0.0608798 0.044394 -0.01 0.00156793 0.0799178 -0.01 0.0042133 0.109919 -0.01 -9.09641e-17 0.11 -0.01 0.0985782 0.0488092 -0.01 -0.00156793 0.0799178 -0.01 -4.24915e-18 0.08 -0.01 -0.0042133 0.109919 -0.01 0.0322588 0.0398609 -0.01 -0.00842042 0.109677 -0.01 -0.00463525 0.0792658 -0.01 -0.00311868 0.0796722 -0.01 0.00463525 0.0507342 -0.01 0.0329716 0.0384619 -0.01 -0.0167914 0.108711 -0.01 -0.0075 0.0779904 -0.01 -0.00610105 0.0787032 -0.01 0.0606342 0.0428433 -0.01 0.0602278 0.0413267 -0.01 0.100375 0.0449976 -0.01 -0.020943 0.107988 -0.01 -0.0250639 0.107106 -0.01 -0.00881678 0.0771353 -0.01 -0.000560476 0.00747903 -0.01 -0.00156793 0.0500822 -0.01 -0.00166891 0.00731196 -0.01 -0.029148 0.106068 -0.01 -0.010037 0.0761472 -0.01 0.0665679 0.0149178 -0.01 0.0571091 0.035925 -0.01 0.065 0.015 -0.01 -0.0129904 0.0725 -0.01 -0.0121353 0.0738168 -0.01 -0.0371819 0.103525 -0.01 0.0559989 0.0348148 -0.01 0.0547787 0.0338267 -0.01 0.0634321 0.0149178 -0.01 -0.0699867 0.0848638 -0.01 -0.0731858 0.0821209 -0.01 -0.0534619 0.0589523 -0.01 -0.0899722 0.0632851 -0.01 -0.0923302 0.0597924 -0.01 -0.0606342 0.0490806 -0.01 0.102025 0.0411199 -0.01 0.0711011 0.0137032 -0.01 0.0588989 0.0137032 -0.01 0.052063 0.0322588 -0.01 0.0505972 0.0316961 -0.01 -0.102025 0.0411199 -0.01 -0.103525 0.0371819 -0.01 -0.0725 0.0129904 -0.01 0.0771353 0.00881678 -0.01 0.107988 0.020943 -0.01 0.107106 0.0250639 -0.01 -0.0771353 0.00881678 -0.01 -0.107988 0.020943 -0.01 -0.0779904 0.0075 -0.01 0.054963 0.0111472 -0.01 0.0459619 0.0309619 -0.01 0.0538528 0.010037 -0.01 -0.0796722 0.00311868 -0.01 -0.109919 0.0042133 -0.01 -0.0799178 0.00156793 -0.01 0.0528647 0.00881678 -0.01 0.044394 0.0310441 -0.01 -0.0725 -0.0129904 -0.01 -0.102025 -0.0411199 -0.01 -0.0711011 -0.0137032 -0.01 0.0799178 -0.00156793 -0.01 0.109919 -0.0042133 -0.01 0.08 9.41679e-18 -0.01 0.0796722 -0.00311868 -0.01 0.109677 -0.00842042 -0.01 0.0512968 0.00610105 -0.01 0.0398609 0.0322588 -0.01 0.0507342 0.00463525 -0.01 -0.052063 -0.0322588 -0.01 -0.0588989 -0.0137032 -0.01 -0.0603647 -0.0142658 -0.01 0.107988 -0.020943 -0.01 0.0779904 -0.0075 -0.01 0.0771353 -0.00881678 -0.01 -0.0602278 -0.0505972 -0.01 -0.0606342 -0.0490806 -0.01 -0.0899722 -0.0632851 -0.01 0.075037 -0.0111472 -0.01 0.106068 -0.029148 -0.01 0.0761472 -0.010037 -0.01 -0.0547787 -0.0580972 -0.01 -0.0559989 -0.0571091 -0.01 -0.0762776 -0.0792574 -0.01 0.103525 -0.0371819 -0.01 0.104874 -0.0331893 -0.01 0.0738168 -0.0121353 -0.01 -0.0597924 -0.0923302 -0.01 -0.0490806 -0.0606342 -0.01 -0.0632851 -0.0899722 -0.01 0.00549789 -0.0051013 -0.01 0.00467617 -0.00586374 -0.01 0.0348148 -0.035925 -0.01 0.0966363 -0.0525492 -0.01 0.0609619 -0.0459619 -0.01 0.0945527 -0.0562121 -0.01 -0.0371819 -0.103525 -0.01 -0.0331893 -0.104874 -0.01 -0.0121353 -0.0738168 -0.01 0.0602278 -0.0505972 -0.01 0.0899722 -0.0632851 -0.01 0.0606342 -0.0490806 -0.01 -0.020943 -0.107988 -0.01 -0.0075 -0.0779904 -0.01 -0.00881678 -0.0771353 -0.01 0.0538528 -0.010037 -0.01 0.0528647 -0.00881678 -0.01 0.044394 -0.0310441 -0.01 0.00311868 -0.0796722 -0.01 0.00156793 -0.0799178 -0.01 0.0042133 -0.109919 -0.01 0.0547787 -0.0580972 -0.01 0.0534619 -0.0589523 -0.01 0.0731858 -0.0821209 -0.01 0.0322588 -0.0398609 -0.01 0.00610105 -0.0512968 -0.01 0.0316961 -0.0413267 -0.01 0.0632851 -0.0899722 -0.01 0.0505972 -0.0602278 -0.01 0.0490806 -0.0606342 -0.01 0.0398609 -0.0596651 -0.01 0.0142658 -0.0696353 -0.01 0.0137032 -0.0711011 -0.01 0.0459619 -0.0609619 -0.01 0.044394 -0.0608798 -0.01 0.0525492 -0.0966363 -0.01 0.0475299 -0.0608798 -0.01 0.0597924 -0.0923302 -0.01 0.0075 -1.37773e-18 -0.01 0.05 -1.60781e-17 -0.01 0.00741623 0.00111782 -0.01 0.0149178 -0.0665679 -0.01 0.0371452 -0.0580972 -0.01 0.035925 -0.0571091 -0.01 0.0146722 -0.0681187 -0.01 0.0762776 -0.0792574 -0.01 0.0792574 -0.0762776 -0.01 0.0559989 -0.0571091 -0.01 0.0666848 -0.0874822 -0.01 0.0129904 -0.0725 -0.01 0.0411199 -0.102025 -0.01 0.0348148 -0.0559989 -0.01 0.015 -0.065 -0.01 0.0413267 -0.0316961 -0.01 0.0428433 -0.0312897 -0.01 0.0520096 -0.0075 -0.01 0.0580972 -0.0547787 -0.01 0.0821209 -0.0731858 -0.01 0.00463525 -0.0792658 -0.01 0.00842042 -0.109677 -0.01 0.0126152 -0.109274 -0.01 0.029148 -0.106068 -0.01 0.0331893 -0.104874 -0.01 0.0111472 -0.075037 -0.01 0.0923302 -0.0597924 -0.01 0.0561832 -0.0121353 -0.01 0.054963 -0.0111472 -0.01 0.0475299 -0.0310441 -0.01 -0.00610105 -0.0787032 -0.01 -0.0126152 -0.109274 -0.01 -0.00463525 -0.0792658 -0.01 0.00463525 -0.0507342 -0.01 0.0608798 -0.0475299 -0.01 0.0634321 -0.0149178 -0.01 0.0618813 -0.0146722 -0.01 0.0547787 -0.0338267 -0.01 -0.029148 -0.106068 -0.01 -0.0111472 -0.075037 -0.01 -0.010037 -0.0761472 -0.01 -0.0250639 -0.107106 -0.01 0.00549789 0.0051013 -0.01 0.035925 0.0348148 -0.01 0.0348148 0.035925 -0.01 0.102025 -0.0411199 -0.01 0.0602278 -0.0413267 -0.01 0.100375 -0.0449976 -0.01 -0.0398609 -0.0596651 -0.01 -0.0142658 -0.0696353 -0.01 -0.0384619 -0.0589523 -0.01 0.0725 -0.0129904 -0.01 -0.0371452 -0.0580972 -0.01 -0.0149178 -0.0665679 -0.01 -0.035925 -0.0571091 -0.01 -0.0137032 -0.0588989 -0.01 -0.0322588 -0.052063 -0.01 -0.0142658 -0.0603647 -0.01 0.00274006 0.00698155 -0.01 -0.0459619 -0.0609619 -0.01 -0.0562121 -0.0945527 -0.01 -0.0525492 -0.0966363 -0.01 -0.052063 -0.0596651 -0.01 -0.0699867 -0.0848638 -0.01 -0.0666848 -0.0874822 -0.01 0.00311868 0.0503278 -0.01 0.107106 -0.0250639 -0.01 -0.0534619 -0.0589523 -0.01 -0.0731858 -0.0821209 -0.01 -0.0821209 -0.0731858 -0.01 -0.0792574 -0.0762776 -0.01 -0.0580972 -0.0547787 -0.01 0.0338267 0.0371452 -0.01 0.00467617 0.00586374 -0.01 0.108711 -0.0167914 -0.01 0.0787032 -0.00610105 -0.01 -0.0111472 -0.054963 -0.01 -0.010037 -0.0538528 -0.01 -0.0309619 -0.0459619 -0.01 -0.0608798 -0.0475299 -0.01 -0.0609619 -0.0459619 -0.01 -0.0945527 -0.0562121 -0.01 0.0413267 0.0316961 -0.01 -0.065 -0.015 -0.01 -0.0665679 -0.0149178 -0.01 -0.0571091 -0.035925 -0.01 -0.0538528 -0.010037 -0.01 -0.054963 -0.0111472 -0.01 -0.0459619 -0.0309619 -0.01 0.0520096 0.0075 -0.01 0.0428433 0.0312897 -0.01 -0.0561832 -0.0121353 -0.01 -0.0475299 -0.0310441 -0.01 -0.104874 -0.0331893 -0.01 -0.0738168 -0.0121353 -0.01 -0.075037 -0.0111472 -0.01 -0.106068 -0.029148 -0.01 -0.0761472 -0.010037 -0.01 -0.107106 -0.0250639 -0.01 -0.109919 -0.0042133 -0.01 -0.109677 -0.00842042 -0.01 -0.0796722 -0.00311868 -0.01 0.11 2.02067e-17 -0.01 0.109919 0.0042133 -0.01 0.0799178 0.00156793 -0.01 -0.0459619 0.0309619 -0.01 -0.054963 0.0111472 -0.01 -0.0538528 0.010037 -0.01 -0.075037 0.0111472 -0.01 -0.104874 0.0331893 -0.01 -0.106068 0.029148 -0.01 0.0792658 0.00463525 -0.01 0.0796722 0.00311868 -0.01 0.109677 0.00842042 -0.01 0.108711 0.0167914 -0.01 0.0779904 0.0075 -0.01 0.0787032 0.00610105 -0.01 -0.0475299 0.0310441 -0.01 -0.0561832 0.0121353 -0.01 -0.065 0.015 -0.01 -0.0634321 0.0149178 -0.01 -0.0559989 0.0348148 -0.01 -0.0338267 0.0371452 -0.01 -0.00467617 0.00586374 -0.01 -0.00375 0.00649519 -0.01 0.0575 0.0129904 -0.01 0.0490806 0.0312897 -0.01 0.0561832 0.0121353 -0.01 -0.0571091 0.035925 -0.01 -0.0580972 0.0371452 -0.01 -0.0665679 0.0149178 -0.01 -0.0490806 0.0312897 -0.01 -0.0575 0.0129904 -0.01 0.075037 0.0111472 -0.01 0.0761472 0.010037 -0.01 0.106068 0.029148 -0.01 0.103525 0.0371819 -0.01 0.0725 0.0129904 -0.01 0.0738168 0.0121353 -0.01 -0.0945527 0.0562121 -0.01 -0.0608798 0.0475299 -0.01 -0.0398609 0.0596651 -0.01 -0.0137032 0.0711011 -0.01 -0.0413267 0.0602278 -0.01 1.60781e-17 0.05 -0.01 0.000560476 0.00747903 -0.01 0.0618813 0.0146722 -0.01 0.0534619 0.0329716 -0.01 0.0603647 0.0142658 -0.01 -0.0874822 0.0666848 -0.01 -0.0596651 0.052063 -0.01 0.0681187 0.0146722 -0.01 0.0580972 0.0371452 -0.01 -0.0762776 0.0792574 -0.01 -0.0559989 0.0571091 -0.01 -0.0547787 0.0580972 -0.01 -0.0459619 0.0609619 -0.01 -0.044394 0.0608798 -0.01 -0.0525492 0.0966363 -0.01 0.0589523 0.0384619 -0.01 -0.0411199 0.102025 -0.01 -0.0111472 0.075037 -0.01 -0.0331893 0.104874 -0.01 0.0696353 0.0142658 -0.01 0.0596651 0.0398609 -0.01 -0.00274006 0.00698155 -0.01 -0.0329716 0.0384619 -0.01 0.0596651 -0.0398609 -0.01 0.0696353 -0.0142658 -0.01 0.0589523 -0.0384619 -0.01 0.0603647 -0.0142658 -0.01 0.052063 -0.0322588 -0.01 0.0534619 -0.0329716 -0.01 0.0848638 -0.0699867 -0.01 0.0596651 -0.052063 -0.01 0.0589523 -0.0534619 -0.01 0.0507342 -0.00463525 -0.01 0.0503278 -0.00311868 -0.01 0.0071668 -0.00221066 -0.01 0.0384619 -0.0589523 -0.01 0.0413267 -0.0602278 -0.01 0.00881678 -0.0771353 -0.01 0.020943 -0.107988 -0.01 0.0250639 -0.107106 -0.01 0.035925 -0.0348148 -0.01 0.0371452 -0.0338267 -0.01 0.00619679 -0.0042249 -0.01 -0.0411199 -0.102025 -0.01 -0.0129904 -0.0725 -0.01 -0.0137032 -0.0711011 -0.01 -0.0129904 -0.0575 -0.01 -0.0316961 -0.0505972 -0.01 -0.0505972 -0.0602278 -0.01 -0.0589523 -0.0534619 -0.01 -0.0596651 -0.052063 -0.01 -0.0848638 -0.0699867 -0.01 -0.0634321 -0.0149178 -0.01 -0.0547787 -0.0338267 -0.01 -0.0618813 -0.0146722 -0.01 -0.0505972 -0.0316961 -0.01 -0.044394 -0.0310441 -0.01 -0.0528647 -0.00881678 -0.01 -0.109677 0.00842042 -0.01 -0.0792658 0.00463525 -0.01 -0.109274 0.0126152 -0.01 -0.0761472 0.010037 -0.01 -0.107106 0.0250639 -0.01 -0.0738168 0.0121353 -0.01 -0.0711011 0.0137032 -0.01 -0.0696353 0.0142658 -0.01 -0.0596651 0.0398609 -0.01 -0.0588989 0.0137032 -0.01 -0.052063 0.0322588 -0.01 -0.0603647 0.0142658 -0.01 -0.0371452 0.0580972 -0.01 -0.0146722 0.0681187 -0.01 -0.0384619 0.0589523 -0.01 -0.0602278 0.0505972 -0.01 -0.0449976 0.100375 -0.01 -0.0580972 0.0547787 -0.01 -0.0792574 0.0762776 -0.01 -0.052063 0.0596651 -0.01 -0.0666848 0.0874822 -0.01 -0.0505972 0.0602278 -0.01 -0.0632851 0.0899722 -0.01 -0.0562121 0.0945527 -0.01 -0.0475299 0.0608798 -0.01 -0.0488092 0.0985782 -0.01 -0.0428433 0.0606342 -0.01 -0.0126152 0.109274 -0.01 0.0384619 0.0589523 -0.01 0.0149178 0.0634321 -0.01 0.0146722 0.0681187 -0.01 0.0338267 0.0547787 -0.01 0.0322588 0.052063 -0.01 0.0137032 0.0588989 -0.01 0.0316961 0.0505972 -0.01 0.0129904 0.0575 -0.01 0.109274 -0.0126152 -0.01 0.0792658 -0.00463525 -0.01 3.97534e-16 -0.11 -0.01 -0.00156793 -0.0799178 -0.01 -0.0042133 -0.109919 -0.01 -0.00842042 -0.109677 -0.01 -0.00311868 -0.0796722 -0.01 0.0711011 -0.0137032 -0.01 0.0571091 -0.035925 -0.01 0.0580972 -0.0371452 -0.01 0.0665679 -0.0149178 -0.01 0.065 -0.015 -0.01 0.0559989 -0.0348148 -0.01 0.0428433 -0.0606342 -0.01 0.0449976 -0.100375 -0.01 0.0874822 -0.0666848 -0.01 0.0512968 -0.00610105 -0.01 0.0398609 -0.0322588 -0.01 0.0488092 -0.0985782 -0.01 0.0699867 -0.0848638 -0.01 0.052063 -0.0596651 -0.01 0.0500822 0.00156793 -0.01 0.0503278 0.00311868 -0.01 0.0562121 -0.0945527 -0.01 0.00156793 0.0500822 -0.01 -0.0322588 0.0398609 -0.01 0.0312897 0.0490806 -0.01 0.0475299 0.0608798 -0.01 0.0699867 0.0848638 -0.01 0.0571091 0.0559989 -0.01 0.0589523 0.0534619 -0.01 0.0681187 -0.0146722 -0.01 0.0606342 -0.0428433 -0.01 0.0608798 -0.044394 -0.01 0.0985782 -0.0488092 -0.01 0.0575 -0.0129904 -0.01 0.0505972 -0.0316961 -0.01 0.0588989 -0.0137032 -0.01 0.00166891 0.00731196 -0.01 0.0500822 -0.00156793 -0.01 0.0384619 0.0329716 -0.01 0.0371452 0.0338267 -0.01 0.00675727 0.00325413 -0.01 -0.0316961 -0.0413267 -0.01 -0.0075 -0.0520096 -0.01 -0.00610105 -0.0512968 -0.01 0.0142658 -0.0603647 -0.01 0.0329716 -0.0534619 -0.01 0.0322588 -0.052063 -0.01 0.0149178 -0.0634321 -0.01 0.0338267 -0.0547787 -0.01 0.0146722 -0.0618813 -0.01 0.0121353 -0.0738168 -0.01 0.0075 -0.0779904 -0.01 0.0167914 -0.108711 -0.01 0.0312897 -0.0490806 -0.01 0.0310441 -0.0475299 -0.01 0.0121353 -0.0561832 -0.01 0.0137032 -0.0588989 -0.01 0.0316961 -0.0505972 -0.01 0.0129904 -0.0575 -0.01 -0.0923302 -0.0597924 -0.01 -0.0384619 -0.0329716 -0.01 -0.0507342 -0.00463525 -0.01 -0.0398609 -0.0322588 -0.01 -0.0413267 -0.0602278 -0.01 0.0475299 0.0310441 -0.01 0.104874 0.0331893 -0.01 0.109274 0.0126152 -0.01 0.0571091 -0.0559989 -0.01 0.0371819 -0.103525 -0.01 0.010037 -0.0761472 -0.01 0.00619679 0.0042249 -0.01 0.00610105 -0.0787032 -0.01 0.010037 -0.0538528 -0.01 0.0111472 -0.054963 -0.01 0.0309619 -0.0459619 -0.01 -0.0348148 0.035925 -0.01 -0.00549789 0.0051013 -0.01 -0.0167914 -0.108711 -0.01 0.00675727 -0.00325413 -0.01 -0.0329716 -0.0534619 -0.01 -0.0146722 -0.0618813 -0.01 -0.0348148 -0.0559989 -0.01 -0.015 -0.065 -0.01 -0.0149178 -0.0634321 -0.01 -0.0488092 -0.0985782 -0.01 -0.044394 -0.0608798 -0.01 -0.0428433 -0.0606342 -0.01 -0.0449976 -0.100375 -0.01 -0.0608798 -0.044394 -0.01 -0.0966363 -0.0525492 -0.01 -0.109274 -0.0126152 -0.01 -0.0792658 -0.00463525 -0.01 -0.100375 -0.0449976 -0.01 -0.0606342 -0.0428433 -0.01 -0.0602278 -0.0413267 -0.01 0.0459619 -0.0309619 -0.01 0.0490806 -0.0312897 -0.01 0.0075 -0.0520096 -0.01 0.00881678 -0.0528647 -0.01 0.0312897 -0.0428433 -0.01 1.60781e-17 -0.08 -0.01 -0.0146722 -0.0681187 -0.01 -0.0338267 -0.0547787 -0.01 -0.0312897 -0.0490806 -0.01 -0.0121353 -0.0561832 -0.01 -0.0475299 -0.0608798 -0.01 -0.0310441 -0.0475299 -0.01 -0.0571091 -0.0559989 -0.01 -0.0874822 -0.0666848 -0.01 -0.0580972 -0.0371452 -0.01 -0.0596651 -0.0398609 -0.01 -0.0589523 -0.0384619 -0.01 -0.0696353 -0.0142658 -0.01 -0.0322588 -0.0398609 -0.01 -0.00463525 -0.0507342 -0.01 -0.0329716 -0.0384619 -0.01 -4.24915e-18 -0.05 -0.01 -0.000560476 -0.00747903 -0.01 -0.00156793 -0.0500822 -0.01 -0.0428433 -0.0312897 -0.01 -0.0413267 -0.0316961 -0.01 -0.0520096 -0.0075 -0.01 -0.0503278 -0.00311868 -0.01 -0.0071668 -0.00221066 -0.01 -0.00741623 -0.00111782 -0.01 0.0338267 -0.0371452 -0.01 -0.0799178 -0.00156793 -0.01 -0.08 -1.60781e-17 -0.01 -0.11 -2.02067e-17 -0.01 -0.0371452 0.0338267 -0.01 -0.00675727 0.00325413 -0.01 -0.00619679 0.0042249 -0.01 -0.108711 0.0167914 -0.01 -0.0787032 0.00610105 -0.01 -0.035925 -0.0348148 -0.01 -0.00549789 -0.0051013 -0.01 -0.00619679 -0.0042249 -0.01 -0.010037 0.0538528 -0.01 -0.0111472 0.054963 -0.01 -0.0309619 0.0459619 -0.01 0.00741623 -0.00111782 -0.01 0.0329716 -0.0384619 -0.01 0.00375 -0.00649519 -0.01 0.0310441 -0.044394 -0.01 -0.0310441 -0.044394 -0.01 -0.00881678 -0.0528647 -0.01 -0.0312897 -0.0428433 -0.01 -0.0985782 -0.0488092 -0.01 -0.0681187 -0.0146722 -0.01 -0.0559989 -0.0348148 -0.01 -0.0490806 -0.0312897 -0.01 -0.103525 -0.0371819 -0.01 -0.108711 -0.0167914 -0.01 -0.0787032 -0.00610105 -0.01 -0.0779904 -0.0075 -0.01 -0.107988 -0.020943 -0.01 -0.0771353 -0.00881678 -0.01 -0.0512968 -0.00610105 -0.01 -0.0512968 0.00610105 -0.01 -0.0398609 0.0322588 -0.01 -0.0413267 0.0316961 -0.01 -0.0428433 0.0312897 -0.01 -0.0520096 0.0075 -0.01 0.00274006 -0.00698155 -0.01 -0.00675727 -0.00325413 -0.01 -0.0371452 -0.0338267 -0.01 -0.00741623 0.00111782 -0.01 -0.0500822 0.00156793 -0.01 -0.0075 -4.59243e-19 -0.01 -0.0338267 -0.0371452 -0.01 -0.00467617 -0.00586374 -0.01 -0.0348148 -0.035925 -0.01 -0.0312897 0.0428433 -0.01 -0.00881678 0.0528647 -0.01 -0.0310441 0.044394 -0.01 -0.00274006 -0.00698155 -0.01 -0.00375 -0.00649519 -0.01 -0.0316961 0.0413267 -0.01 -0.00610105 0.0512968 -0.01 -0.00166891 -0.00731196 -0.01 -0.00311868 -0.0503278 -0.01 0.00311868 -0.0503278 -0.01 0.000560476 -0.00747903 -0.01 0.00156793 -0.0500822 -0.01 0.00166891 -0.00731196 -0.01 -0.0528647 0.00881678 -0.01 -0.044394 0.0310441 -0.01 -0.0575 -0.0129904 -0.01 -0.0534619 -0.0329716 -0.01 -0.0681187 0.0146722 -0.01 -0.0618813 0.0146722 -0.01 -0.0534619 0.0329716 -0.01 -0.0505972 0.0316961 -0.01 -0.0985782 0.0488092 -0.01 -0.0606342 0.0428433 -0.01 -0.0608798 0.044394 -0.01 -0.0602278 0.0413267 -0.01 -0.100375 0.0449976 -0.01 -0.0966363 0.0525492 -0.01 -0.0329716 0.0534619 -0.01 -0.0322588 0.052063 -0.01 -0.0142658 0.0603647 -0.01 -0.0338267 0.0547787 -0.01 -0.0146722 0.0618813 -0.01 -0.0149178 0.0634321 -0.01 -0.0316961 0.0505972 -0.01 -0.0129904 0.0575 -0.01 -0.0137032 0.0588989 -0.01 -0.0310441 0.0475299 -0.01 -0.0121353 0.0561832 -0.01 -0.0312897 0.0490806 -0.01 -0.0503278 0.00311868 -0.01 -0.0507342 0.00463525 -0.01 -0.0071668 0.00221066 -0.01 -0.05 9.41679e-18 -0.01 -0.0075 0.0520096 -0.01 -0.00463525 0.0507342 -0.01 -0.035925 0.0348148 -0.01 -0.0348148 0.0559989 -0.01 -0.015 0.065 -0.01 -0.035925 0.0571091 -0.01 -0.0609619 0.0459619 -0.01 -0.0384619 0.0329716 -0.01 -0.0500822 -0.00156793 -0.01 -0.0589523 0.0384619 -0.01 -0.0547787 0.0338267 -0.01 -0.0571091 0.0559989 -0.01 -0.0142658 0.0696353 -0.01 -0.0490806 0.0606342 -0.01 -0.0597924 0.0923302 -0.01 -0.0149178 0.0665679 -0.01 -0.00311868 0.0503278 -0.01 0.00375 0.00649519 -0.01 0.0071668 0.00221066 -0.01 0.0384619 -0.0329716 -0.01 0.000560476 -0.00747903 -0.072 -0.000560476 -0.00747903 -0.01 0.000560476 -0.00747903 -0.01 -0.0075 3.78991e-18 -0.072 -0.00741623 0.00111782 -0.01 -0.0075 -4.59243e-19 -0.01 0.00166891 -0.00731196 -0.01 0.00166891 -0.00731196 -0.072 0.00274006 -0.00698155 -0.01 0.00274006 -0.00698155 -0.072 0.00375 -0.00649519 -0.072 0.00375 -0.00649519 -0.01 0.00467617 -0.00586374 -0.01 0.00467617 -0.00586374 -0.072 0.00549789 -0.0051013 -0.01 0.00549789 -0.0051013 -0.072 0.00619679 -0.0042249 -0.072 0.00619679 -0.0042249 -0.01 0.00675727 -0.00325413 -0.01 0.00675727 -0.00325413 -0.072 0.0071668 -0.00221066 -0.01 0.0071668 -0.00221066 -0.072 0.00741623 -0.00111782 -0.072 0.00741623 -0.00111782 -0.01 0.0075 -8.95755e-18 -0.072 0.0075 -1.37773e-18 -0.01 -0.000560476 -0.00747903 -0.072 -0.00166891 -0.00731196 -0.072 -0.00166891 -0.00731196 -0.01 -0.00274006 -0.00698155 -0.01 -0.00274006 -0.00698155 -0.072 -0.00375 -0.00649519 -0.072 -0.00375 -0.00649519 -0.01 -0.00467617 -0.00586374 -0.072 -0.00467617 -0.00586374 -0.01 -0.00549789 -0.0051013 -0.01 -0.00549789 -0.0051013 -0.072 -0.00619679 -0.0042249 -0.072 -0.00619679 -0.0042249 -0.01 -0.00675727 -0.00325413 -0.072 -0.00675727 -0.00325413 -0.01 -0.0071668 -0.00221066 -0.01 -0.0071668 -0.00221066 -0.072 -0.00741623 -0.00111782 -0.072 -0.00741623 -0.00111782 -0.01 -0.0071668 0.00221066 -0.072 -0.0071668 0.00221066 -0.01 -0.00741623 0.00111782 -0.072 -0.00549789 0.0051013 -0.072 -0.00549789 0.0051013 -0.01 -0.00619679 0.0042249 -0.072 -0.00675727 0.00325413 -0.072 -0.00619679 0.0042249 -0.01 -0.00675727 0.00325413 -0.01 -0.00375 0.00649519 -0.072 -0.00274006 0.00698155 -0.072 -0.00274006 0.00698155 -0.01 -0.00467617 0.00586374 -0.01 -0.00467617 0.00586374 -0.072 -0.00375 0.00649519 -0.01 0.000560476 0.00747903 -0.01 -0.000560476 0.00747903 -0.072 0.000560476 0.00747903 -0.072 -0.000560476 0.00747903 -0.01 -0.00166891 0.00731196 -0.01 -0.00166891 0.00731196 -0.072 0.00375 0.00649519 -0.072 0.00375 0.00649519 -0.01 0.00274006 0.00698155 -0.072 0.00166891 0.00731196 -0.072 0.00274006 0.00698155 -0.01 0.00166891 0.00731196 -0.01 0.00549789 0.0051013 -0.072 0.00619679 0.0042249 -0.01 0.00549789 0.0051013 -0.01 0.00467617 0.00586374 -0.01 0.00467617 0.00586374 -0.072 0.00675727 0.00325413 -0.01 0.00619679 0.0042249 -0.072 0.00675727 0.00325413 -0.072 0.0071668 0.00221066 -0.01 0.0071668 0.00221066 -0.072 0.00741623 0.00111782 -0.01 0.00741623 0.00111782 -0.072 -0.00549789 0.0051013 -0.072 -0.00375 0.00649519 -0.072 -0.00467617 0.00586374 -0.072 -0.00375 -0.00649519 -0.072 0.00741623 0.00111782 -0.072 0.0071668 0.00221066 -0.072 -0.00619679 0.0042249 -0.072 -0.00274006 0.00698155 -0.072 -0.00166891 0.00731196 -0.072 -0.00675727 0.00325413 -0.072 -0.000560476 0.00747903 -0.072 0.000560476 0.00747903 -0.072 -0.0071668 0.00221066 -0.072 -0.00741623 0.00111782 -0.072 0.00166891 0.00731196 -0.072 -0.0075 3.78991e-18 -0.072 0.00274006 0.00698155 -0.072 0.00549789 0.0051013 -0.072 0.00467617 0.00586374 -0.072 -0.00675727 -0.00325413 -0.072 -0.0071668 -0.00221066 -0.072 0.00375 0.00649519 -0.072 -0.00741623 -0.00111782 -0.072 -0.00467617 -0.00586374 -0.072 0.00675727 0.00325413 -0.072 -0.00619679 -0.0042249 -0.072 -0.00549789 -0.0051013 -0.072 0.00619679 0.0042249 -0.072 0.0075 -8.95755e-18 -0.072 -0.00166891 -0.00731196 -0.072 0.00741623 -0.00111782 -0.072 -0.00274006 -0.00698155 -0.072 0.00619679 -0.0042249 -0.072 0.00675727 -0.00325413 -0.072 0.00166891 -0.00731196 -0.072 0.000560476 -0.00747903 -0.072 0.0071668 -0.00221066 -0.072 -0.000560476 -0.00747903 -0.072 0.00375 -0.00649519 -0.072 0.00467617 -0.00586374 -0.072 0.00549789 -0.0051013 -0.072 0.00274006 -0.00698155 -0.072 - - - - - - - - - - 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 -0.0383026 -0.999266 0 -1.19249e-08 -1 0 -1.19249e-08 -1 0 1 -8.74228e-08 0 0.999266 0.0383027 0 1 -8.74228e-08 0 -0.0383031 -0.999266 0 -0.076549 -0.997066 0 -0.0765494 -0.997066 0 -0.114683 -0.993402 0 -0.152649 -0.98828 0 -0.114683 -0.993402 0 -0.152649 -0.98828 0 -0.190391 -0.981708 0 -0.190391 -0.981708 0 -0.227854 -0.973695 0 -0.264981 -0.964253 0 -0.227854 -0.973695 0 -0.264981 -0.964253 0 -0.301721 -0.953396 0 -0.30172 -0.953396 0 -0.338017 -0.94114 0 -0.373817 -0.927502 0 -0.338017 -0.94114 0 -0.373817 -0.927502 0 -0.409068 -0.912504 0 -0.409069 -0.912503 0 -0.44372 -0.896165 0 -0.47772 -0.878512 0 -0.44372 -0.896165 0 -0.47772 -0.878512 0 -0.511019 -0.85957 0 -0.511019 -0.85957 0 -0.543567 -0.839366 0 -0.575319 -0.817929 0 -0.543568 -0.839365 0 -0.575319 -0.817929 0 -0.606225 -0.795293 0 -0.606225 -0.795293 0 -0.636243 -0.771489 0 -0.665326 -0.746553 0 -0.636242 -0.771489 0 -0.665325 -0.746553 0 -0.693432 -0.720522 0 -0.693433 -0.720521 0 -0.720521 -0.693433 0 -0.746553 -0.665326 0 -0.720522 -0.693432 0 -0.746553 -0.665326 0 -0.771489 -0.636242 0 -0.771489 -0.636242 0 -0.795293 -0.606226 0 -0.817929 -0.575319 0 -0.795293 -0.606226 0 -0.817929 -0.575319 0 -0.839365 -0.543568 0 -0.839365 -0.543568 0 -0.85957 -0.511018 0 -0.878512 -0.47772 0 -0.85957 -0.511019 0 -0.878512 -0.47772 0 -0.896166 -0.44372 0 -0.896166 -0.44372 0 -0.912504 -0.409069 0 -0.927503 -0.373817 0 -0.912504 -0.409068 0 -0.927503 -0.373817 0 -0.94114 -0.338017 0 -0.94114 -0.338017 0 -0.953396 -0.301721 0 -0.964253 -0.264982 0 -0.953396 -0.301721 0 -0.964254 -0.264981 0 -0.973695 -0.227854 0 -0.973695 -0.227853 0 -0.981708 -0.190391 0 -0.98828 -0.152649 0 -0.981708 -0.190391 0 -0.98828 -0.152649 0 -0.993402 -0.114683 0 -0.993402 -0.114684 0 -0.997066 -0.0765493 0 -0.999266 -0.0383029 0 -0.997066 -0.0765493 0 -0.999266 -0.0383024 0 -1 1.74846e-07 0 -1 -3.01992e-07 0 0.0383026 -0.999266 0 0.0383026 -0.999266 0 0.0765494 -0.997066 0 0.114683 -0.993402 0 0.0765489 -0.997066 0 0.114683 -0.993402 0 0.152649 -0.98828 0 0.152649 -0.98828 0 0.190391 -0.981708 0 0.227854 -0.973695 0 0.190391 -0.981708 0 0.227854 -0.973695 0 0.264981 -0.964254 0 0.264981 -0.964254 0 0.30172 -0.953396 0 0.338017 -0.94114 0 0.301721 -0.953396 0 0.338017 -0.94114 0 0.373817 -0.927502 0 0.373817 -0.927502 0 0.409068 -0.912504 0 0.44372 -0.896165 0 0.409068 -0.912504 0 0.44372 -0.896165 0 0.47772 -0.878512 0 0.47772 -0.878512 0 0.511019 -0.859569 0 0.543568 -0.839365 0 0.511019 -0.85957 0 0.543567 -0.839366 0 0.575319 -0.817929 0 0.575319 -0.817929 0 0.606225 -0.795293 0 0.636242 -0.771489 0 0.606226 -0.795293 0 0.636243 -0.771489 0 0.665326 -0.746553 0 0.665326 -0.746553 0 0.693432 -0.720522 0 0.720521 -0.693433 0 0.693432 -0.720522 0 0.720522 -0.693433 0 0.746553 -0.665326 0 0.746553 -0.665326 0 0.771489 -0.636242 0 0.795293 -0.606225 0 0.771489 -0.636243 0 0.795293 -0.606226 0 0.817929 -0.575319 0 0.817929 -0.575319 0 0.839365 -0.543568 0 0.85957 -0.511019 0 0.839366 -0.543567 0 0.85957 -0.511019 0 0.878512 -0.47772 0 0.878512 -0.47772 0 0.896166 -0.44372 0 0.912504 -0.409069 0 0.896166 -0.44372 0 0.912504 -0.409069 0 0.927502 -0.373817 0 0.927502 -0.373817 0 0.94114 -0.338017 0 0.953396 -0.30172 0 0.94114 -0.338017 0 0.953396 -0.301721 0 0.964253 -0.264982 0 0.964253 -0.264982 0 0.973695 -0.227853 0 0.981708 -0.190391 0 0.973695 -0.227854 0 0.981708 -0.190391 0 0.98828 -0.152649 0 0.98828 -0.152649 0 0.993402 -0.114684 0 0.997066 -0.0765493 0 0.993402 -0.114683 0 0.997066 -0.0765493 0 0.999266 -0.0383029 0 0.999266 -0.0383027 0 0.997066 0.0765491 0 0.997066 0.0765491 0 0.999266 0.0383027 0 0.981708 0.190391 0 0.981708 0.190391 0 0.98828 0.152649 0 0.993402 0.114684 0 0.98828 0.152649 0 0.993402 0.114683 0 0.964254 0.264981 0 0.953396 0.301721 0 0.953396 0.301721 0 0.973695 0.227853 0 0.973695 0.227853 0 0.964253 0.264982 0 0.912504 0.409069 0 0.927502 0.373817 0 0.912504 0.409069 0 0.927502 0.373817 0 0.94114 0.338017 0 0.94114 0.338017 0 0.85957 0.511019 0 0.85957 0.511019 0 0.878512 0.47772 0 0.896166 0.44372 0 0.878512 0.47772 0 0.896166 0.44372 0 0.817929 0.575319 0 0.795293 0.606225 0 0.795293 0.606225 0 0.839365 0.543568 0 0.839365 0.543568 0 0.817929 0.575319 0 0.720522 0.693433 0 0.746553 0.665326 0 0.720522 0.693433 0 0.746553 0.665326 0 0.771489 0.636242 0 0.771489 0.636243 0 0.636243 0.771489 0 0.636243 0.771489 0 0.665326 0.746553 0 0.693433 0.720522 0 0.665326 0.746553 0 0.693433 0.720522 0 0.575319 0.817929 0 0.543568 0.839365 0 0.543567 0.839365 0 0.606225 0.795293 0 0.606225 0.795293 0 0.575319 0.817929 0 0.44372 0.896166 0 0.47772 0.878512 0 0.44372 0.896166 0 0.47772 0.878512 0 0.511019 0.85957 0 0.511019 0.85957 0 0.338017 0.94114 0 0.338017 0.94114 0 0.373817 0.927502 0 0.409069 0.912504 0 0.373817 0.927502 0 0.409069 0.912504 0 0.264981 0.964253 0 0.227854 0.973695 0 0.227853 0.973695 0 0.301721 0.953396 0 0.301721 0.953396 0 0.264982 0.964253 0 0.114684 0.993402 0 0.152649 0.98828 0 0.114684 0.993402 0 0.152649 0.98828 0 0.190391 0.981708 0 0.190391 0.981708 0 4.37114e-08 1 0 -7.54979e-08 1 0 0.0383027 0.999266 0 0.0765491 0.997066 0 0.0383026 0.999266 0 0.0765494 0.997066 0 -0.0765493 0.997066 0 -0.114683 0.993402 0 -0.114683 0.993402 0 -0.0383028 0.999266 0 -0.0383027 0.999266 0 -0.0765493 0.997066 0 -0.227854 0.973695 0 -0.190391 0.981708 0 -0.227854 0.973695 0 -0.190391 0.981708 0 -0.152649 0.98828 0 -0.152649 0.98828 0 -0.338017 0.94114 0 -0.338017 0.94114 0 -0.301721 0.953396 0 -0.264982 0.964253 0 -0.301721 0.953396 0 -0.264982 0.964253 0 -0.409069 0.912504 0 -0.44372 0.896166 0 -0.44372 0.896166 0 -0.373817 0.927502 0 -0.373817 0.927502 0 -0.409069 0.912504 0 -0.543568 0.839365 0 -0.511019 0.85957 0 -0.543568 0.839365 0 -0.511019 0.85957 0 -0.47772 0.878512 0 -0.47772 0.878512 0 -0.636242 0.771489 0 -0.636243 0.771489 0 -0.606225 0.795293 0 -0.575319 0.817929 0 -0.606225 0.795293 0 -0.575319 0.817929 0 -0.693433 0.720522 0 -0.720522 0.693433 0 -0.720522 0.693433 0 -0.665326 0.746553 0 -0.665326 0.746553 0 -0.693432 0.720522 0 -0.746553 0.665326 0 -0.746553 0.665326 0 -0.771489 0.636242 0 -0.771489 0.636242 0 -0.795293 0.606225 0 -0.795293 0.606225 0 -0.817929 0.575319 0 -0.817929 0.575319 0 -0.839365 0.543568 0 -0.839365 0.543568 0 -0.85957 0.511019 0 -0.85957 0.511019 0 -0.878512 0.47772 0 -0.878512 0.47772 0 -0.896166 0.44372 0 -0.896166 0.44372 0 -0.912504 0.409069 0 -0.912504 0.409069 0 -0.927502 0.373817 0 -0.927502 0.373817 0 -0.94114 0.338017 0 -0.94114 0.338017 0 -0.953396 0.301721 0 -0.953396 0.301721 0 -0.964253 0.264982 0 -0.964253 0.264982 0 -0.973695 0.227854 0 -0.973695 0.227854 0 -0.981708 0.190391 0 -0.981708 0.190391 0 -0.98828 0.152649 0 -0.98828 0.152649 0 -0.993402 0.114683 0 -0.993402 0.114683 0 -0.997066 0.0765492 0 -0.997066 0.0765493 0 -0.999266 0.0383027 0 -0.999266 0.0383027 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0.0747303 -0.997204 0 -0.0747303 -0.997204 0 0.0747303 -0.997204 0 -1 -8.74228e-08 0 -0.988831 0.149042 0 -1 -8.74228e-08 0 0.222521 -0.974928 0 0.222521 -0.974928 0 0.365341 -0.930874 0 0.365341 -0.930874 0 0.5 -0.866025 0 0.5 -0.866025 0 0.62349 -0.781831 0 0.62349 -0.781831 0 0.733052 -0.680173 0 0.733052 -0.680173 0 0.826239 -0.56332 0 0.826239 -0.56332 0 0.900969 -0.433884 0 0.900969 -0.433884 0 0.955573 -0.294755 0 0.955573 -0.294755 0 0.988831 -0.149042 0 0.988831 -0.149042 0 1 1.74846e-07 0 1 -3.01992e-07 0 -0.0747303 -0.997204 0 -0.222521 -0.974928 0 -0.222521 -0.974928 0 -0.365341 -0.930874 0 -0.365341 -0.930874 0 -0.5 -0.866025 0 -0.5 -0.866025 0 -0.62349 -0.781831 0 -0.62349 -0.781832 0 -0.733052 -0.680173 0 -0.733052 -0.680173 0 -0.826239 -0.56332 0 -0.826239 -0.56332 0 -0.900969 -0.433884 0 -0.900969 -0.433884 0 -0.955573 -0.294755 0 -0.955573 -0.294755 0 -0.988831 -0.149042 0 -0.988831 -0.149042 0 -0.955573 0.294755 0 -0.955573 0.294755 0 -0.988831 0.149042 0 -0.733052 0.680173 0 -0.733052 0.680173 0 -0.826239 0.56332 0 -0.900969 0.433884 0 -0.826239 0.56332 0 -0.900969 0.433884 0 -0.5 0.866025 0 -0.365341 0.930874 0 -0.365341 0.930874 0 -0.62349 0.781831 0 -0.62349 0.781832 0 -0.5 0.866026 0 0.07473 0.997204 0 -0.0747302 0.997204 0 0.0747301 0.997204 0 -0.07473 0.997204 0 -0.222521 0.974928 0 -0.222521 0.974928 0 0.5 0.866025 0 0.5 0.866025 0 0.365341 0.930874 0 0.222521 0.974928 0 0.365341 0.930874 0 0.222521 0.974928 0 0.733052 0.680173 0 0.826239 0.56332 0 0.733052 0.680173 0 0.62349 0.781832 0 0.62349 0.781832 0 0.900969 0.433884 0 0.826239 0.56332 0 0.900969 0.433884 0 0.955573 0.294755 0 0.955573 0.294755 0 0.988831 0.149042 0 0.988831 0.149042 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 - - - - - - - - - - - - - - -

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

-
-
-
- - - - 0.07241 0.0847184 0.0126994 0.0732981 0.0820207 0.01 0.076297 0.0812353 0.0126994 -0.101913 0.0451006 0.0126994 -0.103522 0.0412741 0.0126994 -0.101627 0.042095 0.01 -0.066145 0.087891 0.01 -0.066147 0.0896939 0.0126994 -0.0685842 0.0860012 0.01 -0.0741374 -0.0910265 0.021483 -0.0696789 -0.094483 0.021483 -0.068353 -0.0926852 0.0185002 -0.0703795 0.0864126 0.0126994 -0.100406 0.0449288 0.01 0.111179 -0.00773005 0.0126994 0.109827 -0.00616737 0.01 0.109611 -0.00924536 0.01 -0.0709692 0.0840439 0.01 -0.100118 0.0489572 0.0126994 -0.0991067 0.0477269 0.01 -0.0840512 0.0854476 0.0244418 -0.0823259 0.0836937 0.021483 -0.0799963 0.0892552 0.0244418 -0.0981274 0.0528339 0.0126994 -0.0977292 0.0504877 0.01 -0.0959339 0.0567195 0.0126994 -0.0947445 0.0558881 0.01 -0.0931399 0.0585232 0.01 -0.102768 0.039228 0.01 -0.0962747 0.0532089 0.01 -0.078153 0.0794514 0.0126994 -0.0799329 0.0755694 0.01 -0.077782 0.0777815 0.01 -0.0909087 0.0644673 0.0126994 -0.0935298 0.0606018 0.0126994 -0.0914618 0.0611124 0.01 -0.0878913 0.0661447 0.01 -0.0897118 0.0636538 0.01 -0.0820207 0.0732981 0.01 -0.0849926 0.0720879 0.0126994 -0.0840443 0.0709687 0.01 -0.0880645 0.0683012 0.0126994 -0.0860017 0.0685836 0.01 -0.0816895 0.0758106 0.0126994 -0.0755698 0.0799325 0.01 -0.0743826 0.0829918 0.0126994 -0.0732982 0.0820206 0.01 -0.063654 0.0897116 0.01 -0.0570161 0.0957579 0.0126994 -0.0558884 0.0947443 0.01 -0.0532093 0.0962744 0.01 -0.036938 0.106976 0.0155526 -0.0424464 0.104913 0.0155526 -0.0417986 0.103312 0.0126994 -0.0477275 0.0991065 0.01 -0.0521346 0.0985007 0.0126994 -0.0504884 0.0977288 0.01 -0.0375874 0.108857 0.0185002 -0.0431926 0.106757 0.0185002 -0.0800817 0.108589 0.0368012 -0.0781099 0.105915 0.0348514 -0.0746859 0.112369 0.0368012 -0.0486269 0.104394 0.0185002 -0.0477868 0.10259 0.0155526 -0.0573176 0.108293 0.0273172 -0.0560692 0.105935 0.0244418 -0.0517357 0.111068 0.0273172 -0.103991 0.0806538 0.0348514 -0.100364 0.0851253 0.0348514 -0.102897 0.0872742 0.0368012 -0.0549184 0.10376 0.021483 -0.0506089 0.108649 0.0244418 -0.0694055 0.104424 0.0300502 -0.0656978 0.110339 0.0325813 -0.0710835 0.106949 0.0325813 -0.0673277 0.113076 0.0348514 -0.0728469 0.109602 0.0348514 -0.0626843 0.105278 0.0273172 -0.058655 0.11082 0.0300502 -0.064147 0.107734 0.0300502 -0.134661 0.0725043 0.039724 -0.131384 0.0707399 0.0402139 -0.131651 0.0778366 0.039724 -0.0600731 0.113499 0.0325813 -0.0690273 0.115931 0.0368012 -0.0440305 0.108828 0.021483 -0.0495701 0.106419 0.021483 -0.0765904 0.115234 0.0383714 -0.0821238 0.111358 0.0383714 -0.0873787 0.107284 0.0383714 -0.0842256 0.114208 0.0395028 -0.0896149 0.11003 0.0395028 -0.0559647 0.138325 0.0402139 -0.0614487 0.13192 0.0401362 -0.0545816 0.134907 0.0401362 -0.0573606 0.141775 0.039724 -0.0645773 0.138637 0.039724 -0.0630058 0.135263 0.0402139 -0.14402 0.0704249 0.0371966 -0.144299 0.0776938 0.0352405 -0.147226 0.071993 0.0352405 -0.104555 0.116656 0.0387046 -0.10725 0.109032 0.039724 -0.102076 0.11389 0.039724 -0.10464 0.106378 0.0402139 -0.0995917 0.111119 0.0402139 -0.150187 0.0808637 0.0301473 -0.147322 0.0793213 0.0328772 -0.146829 0.0868108 0.0301473 -0.094232 0.115699 0.0402139 -0.0965824 0.118585 0.039724 -0.106999 0.119384 0.0371966 -0.109854 0.111679 0.0387046 -0.157225 0.0929573 0.0124252 -0.16082 0.0865891 0.0124252 -0.159312 0.0857767 0.0163769 -0.127602 0.108228 0.0328772 -0.130084 0.110333 0.0301473 -0.132214 0.102543 0.0328772 -0.112423 0.114291 0.0371966 -0.114926 0.116836 0.0352405 -0.11751 0.109054 0.0371966 -0.125028 0.11603 0.0301473 -0.122643 0.113817 0.0328772 -0.139366 0.10809 0.0237508 -0.141611 0.100422 0.0270916 -0.137181 0.106395 0.0270916 -0.134785 0.104537 0.0301473 -0.132395 0.112293 0.0270916 -0.149439 0.0883536 0.0270916 -0.148016 0.0959054 0.0237508 -0.15182 0.0897614 0.0237508 -0.141309 0.109597 0.0201657 -0.143867 0.102023 0.0237508 -0.114825 0.106562 0.0387046 -0.145873 0.103445 0.0201657 -0.147592 0.104664 0.0163769 -0.150079 0.0972421 0.0201657 -0.142974 0.110888 0.0163769 -0.12898 0.131123 0.00835136 -0.12954 0.131692 0.00419604 -0.134817 0.125114 0.00835136 -0.159249 0.0941535 3.35051e-17 -0.16289 0.0877033 3.2731e-17 -0.162647 0.0875728 0.00419604 -0.164083 0.0802356 -0.0124252 -0.16523 0.0807966 -0.00835136 -0.16082 0.0865891 -0.0124252 -0.14899 0.105655 0.0124252 -0.151847 0.0983881 0.0163769 -0.159012 0.0940133 0.00419604 -0.155258 0.100598 3.29075e-17 -0.159012 0.0940133 -0.00419604 -0.162647 0.0875728 -0.00419604 -0.155027 0.100448 -0.00419604 -0.155027 0.100448 0.00419604 -0.154357 0.100014 0.00835136 -0.150682 0.106855 0.00419604 -0.167025 0.073915 -0.0124252 -0.162543 0.0794828 -0.0163769 -0.165458 0.0732215 -0.0163769 -0.159312 0.0857767 -0.0163769 -0.161283 0.0713739 -0.0237508 -0.163531 0.0723687 -0.0201657 -0.158442 0.0774771 -0.0237508 -0.16807 0.0670092 -0.0163769 -0.166113 0.0662287 -0.0201657 -0.147322 0.0793213 -0.0328772 -0.150187 0.0808637 -0.0301473 -0.144029 0.0851549 -0.0328772 -0.163829 0.0653183 -0.0237508 -0.156192 0.0496245 -0.0352405 -0.161118 0.0451288 -0.0328772 -0.159464 0.050664 -0.0328772 -0.158753 0.0702544 -0.0270916 -0.16126 0.0642938 -0.0270916 -0.154337 0.0551252 -0.0352405 -0.15757 0.0562799 -0.0328772 -0.15279 0.0485437 -0.0371966 -0.157812 0.0442028 -0.0352405 -0.158444 0.0631711 -0.0301473 -0.155421 0.0619662 -0.0328772 -0.160634 0.0573743 -0.0301473 -0.143687 0.0402465 -0.0402139 -0.148576 0.0362725 -0.039724 -0.147271 0.0412503 -0.039724 -0.149299 0.0474345 -0.0387046 -0.154375 0.0432401 -0.0371966 -0.061113 0.0914614 0.01 -0.06169 0.0928157 0.0126994 -0.15061 0.0265883 -0.039724 -0.146042 0.0306195 -0.0402139 -0.146945 0.0259413 -0.0402139 -0.139746 0.0246702 -0.0395028 -0.135421 0.0283927 -0.0383714 -0.136258 0.0240546 -0.0383714 -0.134418 0.032816 -0.0383714 -0.138887 0.0291193 -0.0395028 -0.13187 0.0418969 -0.0383714 -0.136647 0.0382746 -0.0395028 -0.135245 0.0429691 -0.0395028 -0.14496 0.0353898 -0.0402139 -0.141378 0.0345152 -0.0401362 -0.127094 0.0183821 -0.0325813 -0.126461 0.0223251 -0.0325813 -0.123476 0.0217981 -0.0300502 -0.13287 0.0234565 -0.0368012 -0.132054 0.0276866 -0.0368012 -0.124094 0.0179482 -0.0300502 -0.124581 0.0141825 -0.0300502 -0.127593 0.0145254 -0.0325813 -0.130758 0.0148857 -0.0348514 -0.122096 0.0102639 -0.0273172 -0.12174 0.0138591 -0.0273172 -0.119089 0.0135572 -0.0244418 -0.119437 0.0100403 -0.0244418 -0.12234 0.00675494 -0.0273172 -0.149685 0.0313832 -0.039724 -0.118033 0.0208371 -0.0244418 -0.118623 0.0171569 -0.0244418 -0.121265 0.0175389 -0.0273172 -0.111449 0 -0.0127028 -0.111406 0.00303201 -0.0126994 -0.11 0 -0.01 -0.113032 0 -0.0153294 -0.113132 0.003079 -0.0155526 -0.111277 0.00614412 -0.0126994 -0.115121 0.00313313 -0.0185002 -0.11473 0 -0.0178833 -0.112448 0.0128012 -0.0155526 -0.112776 0.00948044 -0.0155526 -0.114759 0.0096471 -0.0185002 -0.104953 0.0374866 0.0126994 -0.103827 0.0363304 0.01 -0.106215 0.033746 0.0126994 -0.0585238 0.0931395 0.01 -0.104805 0.0334044 0.01 -0.105701 0.0304516 0.01 -0.107317 0.0300591 0.0126994 -0.106513 0.027475 0.01 -0.107242 0.0244771 0.01 -0.108267 0.0264318 0.0126994 -0.0470575 0.101025 0.0126994 -0.0449289 0.100406 0.01 -0.107886 0.0214598 0.01 -0.109075 0.022869 0.0126994 -0.10975 0.0193749 0.0126994 -0.108446 0.0184253 0.01 -0.0420955 0.101627 0.01 -0.10892 0.0153766 0.01 -0.110299 0.015953 0.0126994 -0.0392287 0.102767 0.01 -0.101474 0.0787013 0.0325813 -0.102278 0.0725301 0.0300502 -0.0990786 0.0768435 0.0300502 -0.0363743 0.105344 0.0126994 -0.0613191 0.102985 0.0244418 -0.0312801 0.108766 0.0155526 -0.110766 0.0232234 0.0155526 -0.0363309 0.103827 0.01 -0.109308 0.012316 0.01 -0.110732 0.0126059 0.0126994 -0.0334045 0.104805 0.01 -0.111055 0.00933575 0.0126994 -0.109611 0.00924536 0.01 -0.0308027 0.107106 0.0126994 -0.109827 0.00616737 0.01 -0.0254931 0.110266 0.0155526 -0.0274758 0.106513 0.01 -0.0304523 0.105701 0.01 -0.025104 0.108583 0.0126994 -0.111277 0.00614412 0.0126994 -0.0244774 0.107242 0.01 -0.113002 0.00623934 0.0155526 -0.111406 0.00303201 0.0126994 -0.0214601 0.107886 0.01 -0.109957 0.00308534 0.01 -0.11 0 0.01 -0.0193002 0.109763 0.0126994 -0.0136223 0.112351 0.0155526 -0.0195993 0.111464 0.0155526 -0.0153772 0.10892 0.01 -0.0184261 0.108446 0.01 -0.0134144 0.110637 0.0126994 -0.00758704 0.11292 0.0155526 -0.0123162 0.109308 0.01 -0.00924585 0.109611 0.01 -0.00747125 0.111196 0.0126994 -0.00151905 0.113164 0.0155526 -0.00616814 0.109827 0.01 -0.00308534 0.109957 0.01 -0.00149586 0.111437 0.0126994 0.0045555 0.113082 0.0155526 3.08198e-16 0.11 0.01 0.00448598 0.111357 0.0126994 0.00308474 0.109957 0.01 0.0106104 0.112676 0.0155526 0.0104485 0.110956 0.0126994 0.00616737 0.109827 0.01 0.00924536 0.109611 0.01 0.0166197 0.111947 0.0155526 0.012316 0.109308 0.01 0.0163661 0.110239 0.0126994 0.0225581 0.110903 0.0155526 0.0153766 0.10892 0.01 0.0184253 0.108446 0.01 0.0222138 0.109211 0.0126994 0.0284014 0.109552 0.0155526 0.0244771 0.107242 0.01 0.0214598 0.107886 0.01 0.0341265 0.107906 0.0155526 0.0279679 0.107881 0.0126994 0.027475 0.106513 0.01 0.0304516 0.105701 0.01 0.0334044 0.104805 0.01 0.0336057 0.106259 0.0126994 0.0404102 0.107841 0.0185002 0.0347264 0.109803 0.0185002 0.0363304 0.103827 0.01 0.0391061 0.104361 0.0126994 0.039228 0.102768 0.01 0.0451387 0.103783 0.0155526 0.0444498 0.102199 0.0126994 0.0503887 0.101338 0.0155526 0.042095 0.101627 0.01 0.0449288 0.100406 0.01 0.0496197 0.0997913 0.0126994 0.0554468 0.0986612 0.0155526 0.0477269 0.0991067 0.01 0.0504877 0.0977292 0.01 0.0602999 0.0957721 0.0155526 0.0546006 0.0971555 0.0126994 0.0532089 0.0962747 0.01 0.0558881 0.0947445 0.01 0.0593797 0.0943105 0.0126994 0.0649372 0.0926906 0.0155526 0.0585232 0.0931399 0.01 0.0611124 0.0914618 0.01 0.0639461 0.091276 0.0126994 0.0636538 0.0897118 0.01 0.0682917 0.0880719 0.0126994 0.0661447 0.0878913 0.01 0.0685836 0.0860017 0.01 0.0705692 0.0910091 0.0185002 0.0660788 0.09432 0.0185002 0.0709687 0.0840443 0.01 0.0774795 0.0824943 0.0155526 0.0735322 0.0860314 0.0155526 0.0811896 0.0788457 0.0155526 0.0755694 0.0799329 0.01 0.0777815 0.077782 0.01 0.0799505 0.0776423 0.0126994 0.0799325 0.0755698 0.01 0.0833701 0.0739583 0.0126994 0.0826169 0.0802317 0.0185002 0.0861505 0.0764248 0.0185002 0.0820206 0.0732982 0.01 0.0840439 0.0709692 0.01 0.0865573 0.0702015 0.0126994 0.0909021 0.067418 0.0155526 0.0878988 0.0712895 0.0155526 0.0860012 0.0685842 0.01 0.0895148 0.0663891 0.0126994 0.087891 0.066145 0.01 0.0897116 0.063654 0.01 0.0922468 0.0625375 0.0126994 0.0962272 0.0595711 0.0155526 0.0936764 0.0635068 0.0155526 0.0914614 0.061113 0.01 0.0947586 0.0586619 0.0126994 0.0931395 0.0585238 0.01 0.0947443 0.0558884 0.01 0.0970565 0.0547763 0.0126994 0.100293 0.0566031 0.0185002 0.0979188 0.0606183 0.0185002 0.0962744 0.0532093 0.01 0.0991476 0.0508937 0.0126994 0.0977288 0.0504884 0.01 0.0991065 0.0477275 0.01 0.10104 0.0470257 0.0126994 0.100684 0.0516824 0.0155526 0.104409 0.048594 0.0185002 0.102454 0.052591 0.0185002 0.100406 0.0449289 0.01 0.102741 0.043183 0.0126994 0.101627 0.0420955 0.01 0.104259 0.039375 0.0126994 0.102767 0.0392287 0.01 0.107241 0.0361619 0.0155526 0.105875 0.0399852 0.0155526 0.103827 0.0363309 0.01 0.105605 0.03561 0.0126994 0.104805 0.0334045 0.01 0.106785 0.0318955 0.0126994 0.105701 0.0304523 0.01 0.106513 0.0274758 0.01 0.10781 0.0282377 0.0126994 0.109481 0.0286753 0.0155526 0.110373 0.0250239 0.0155526 0.108688 0.024642 0.0126994 0.107242 0.0244774 0.01 0.107886 0.0214601 0.01 0.109429 0.0211131 0.0126994 0.108446 0.0184261 0.01 0.11004 0.0176547 0.0126994 0.10892 0.0153772 0.01 0.11053 0.0142699 0.0126994 0.109308 0.0123162 0.01 0.109611 0.00924585 0.01 0.110907 0.0109611 0.0126994 0.109827 0.00616814 0.01 0.111179 0.00773005 0.0126994 0.114886 0.00798785 0.0185002 0.114605 0.0113266 0.0185002 0.112625 0.011131 0.0155526 0.111353 0.00457808 0.0126994 0.109957 0.00308534 0.01 0.111437 0.00150597 0.0126994 0.11 2.45709e-15 0.01 0.111437 -0.00150597 0.0126994 0.109957 -0.00308534 0.01 0.111353 -0.00457808 0.0126994 0.110907 -0.0109611 0.0126994 0.11004 -0.0176547 0.0126994 0.108446 -0.0184253 0.01 0.109429 -0.0211131 0.0126994 0.109308 -0.012316 0.01 0.105701 -0.0304516 0.01 0.10781 -0.0282377 0.0126994 0.106513 -0.027475 0.01 0.107886 -0.0214598 0.01 0.104259 -0.039375 0.0126994 0.103827 -0.0363304 0.01 0.102768 -0.039228 0.01 0.106785 -0.0318955 0.0126994 0.0977292 -0.0504877 0.01 0.0991476 -0.0508937 0.0126994 0.0991067 -0.0477269 0.01 0.100406 -0.0449288 0.01 0.102741 -0.043183 0.0126994 0.101627 -0.042095 0.01 0.0947445 -0.0558881 0.01 0.0947586 -0.0586619 0.0126994 0.0970565 -0.0547763 0.0126994 0.0962747 -0.0532089 0.01 0.0865573 -0.0702015 0.0126994 0.0895148 -0.0663891 0.0126994 0.0860017 -0.0685836 0.01 0.0897118 -0.0636538 0.01 0.0922468 -0.0625375 0.0126994 0.0914618 -0.0611124 0.01 0.0799329 -0.0755694 0.01 0.0833701 -0.0739583 0.0126994 0.0820207 -0.0732981 0.01 0.0840443 -0.0709687 0.01 0.0709692 -0.0840439 0.01 0.07241 -0.0847184 0.0126994 0.0732982 -0.0820206 0.01 0.0811896 -0.0788457 0.0155526 0.0788415 -0.0839446 0.0185002 0.0826169 -0.0802317 0.0185002 0.061113 -0.0914614 0.01 0.0593797 -0.0943105 0.0126994 0.0639461 -0.091276 0.0126994 0.066145 -0.087891 0.01 0.0682917 -0.0880719 0.0126994 0.0558884 -0.0947443 0.01 0.0532093 -0.0962744 0.01 0.0546006 -0.0971555 0.0126994 0.0554468 -0.0986612 0.0155526 0.0602999 -0.0957721 0.0155526 0.0449289 -0.100406 0.01 0.0420955 -0.101627 0.01 0.0444498 -0.102199 0.0126994 0.0477275 -0.0991065 0.01 0.0496197 -0.0997913 0.0126994 0.0334045 -0.104805 0.01 0.0336057 -0.106259 0.0126994 0.0363309 -0.103827 0.01 0.0391061 -0.104361 0.0126994 0.0392287 -0.102767 0.01 0.0244774 -0.107242 0.01 0.0214601 -0.107886 0.01 0.0222138 -0.109211 0.0126994 0.0304523 -0.105701 0.01 0.0274758 -0.106513 0.01 0.0279679 -0.107881 0.0126994 0.0104485 -0.110956 0.0126994 0.0163661 -0.110239 0.0126994 0.0123162 -0.109308 0.01 0.0184261 -0.108446 0.01 0.00308534 -0.109957 0.01 -3.20632e-16 -0.11 0.01 0.00448598 -0.111357 0.0126994 -0.00151905 -0.113164 0.0155526 0.0045555 -0.113082 0.0155526 -0.00308474 -0.109957 0.01 -0.00616737 -0.109827 0.01 -0.00747125 -0.111196 0.0126994 -0.00149586 -0.111437 0.0126994 -0.0193002 -0.109763 0.0126994 -0.0134144 -0.110637 0.0126994 -0.0153766 -0.10892 0.01 -0.0195993 -0.111464 0.0155526 -0.0136223 -0.112351 0.0155526 -0.0244771 -0.107242 0.01 -0.027475 -0.106513 0.01 -0.025104 -0.108583 0.0126994 -0.0184253 -0.108446 0.01 -0.0214598 -0.107886 0.01 -0.0334044 -0.104805 0.01 -0.0363743 -0.105344 0.0126994 -0.0308027 -0.107106 0.0126994 -0.0304516 -0.105701 0.01 -0.042095 -0.101627 0.01 -0.0417986 -0.103312 0.0126994 -0.039228 -0.102768 0.01 -0.0363304 -0.103827 0.01 -0.0521346 -0.0985007 0.0126994 -0.0470575 -0.101025 0.0126994 -0.0477269 -0.0991067 0.01 -0.0529426 -0.100027 0.0155526 -0.0477868 -0.10259 0.0155526 -0.0570161 -0.0957579 0.0126994 -0.0626461 -0.0942542 0.0155526 -0.0578997 -0.097242 0.0155526 -0.0504877 -0.0977292 0.01 -0.06169 -0.0928157 0.0126994 -0.0585232 -0.0931399 0.01 -0.0611124 -0.0914618 0.01 -0.0558881 -0.0947445 0.01 -0.0768633 -0.0857596 0.0185002 -0.0727267 -0.0892944 0.0185002 -0.0714703 -0.0877518 0.0155526 -0.0671721 -0.091084 0.0155526 -0.0879275 -0.0893882 0.0300502 -0.0941282 -0.0873541 0.0325813 -0.0900532 -0.0915493 0.0325813 -0.0783542 -0.0874231 0.021483 -0.156192 -0.0496245 -0.0352405 -0.15757 -0.0562799 -0.0328772 -0.159464 -0.050664 -0.0328772 -0.0988985 -0.0917811 0.0368012 -0.094617 -0.0961889 0.0368012 -0.0922873 -0.0938205 0.0348514 -0.164083 -0.0802356 0.0124252 -0.16523 -0.0807966 0.00835136 -0.16082 -0.0865891 0.0124252 -0.170848 -0.0681168 -0.00835136 -0.171589 -0.0684123 -0.00419604 -0.17321 -0.0618662 -0.00835136 -0.152856 -0.0823008 0.0270916 -0.155291 -0.0836122 0.0237508 -0.149439 -0.0883536 0.0270916 -0.157225 -0.0929573 0.0124252 -0.161945 -0.0871946 0.00835136 -0.124755 -0.0884689 0.039724 -0.117911 -0.0914492 0.0402139 -0.121719 -0.0863159 0.0402139 -0.141611 -0.100422 0.0270916 -0.143867 -0.102023 0.0237508 -0.137181 -0.106395 0.0270916 -0.0859226 -0.0873501 0.0273172 -0.0817773 -0.0912425 0.0273172 -0.0799963 -0.0892552 0.0244418 -0.116636 -0.0989267 0.039724 -0.109375 -0.101504 0.0402139 -0.113798 -0.0965193 0.0402139 -0.0661447 -0.0878913 0.01 -0.0703795 -0.0864126 0.0126994 -0.066147 -0.0896939 0.0126994 -0.0636538 -0.0897118 0.01 -0.0732981 -0.0820207 0.01 -0.0743826 -0.0829918 0.0126994 -0.0709687 -0.0840443 0.01 -0.0685836 -0.0860017 0.01 -0.0777815 -0.077782 0.01 -0.078153 -0.0794514 0.0126994 -0.0755694 -0.0799329 0.01 -0.0820206 -0.0732982 0.01 -0.0816895 -0.0758106 0.0126994 -0.0799325 -0.0755698 0.01 -0.0860012 -0.0685842 0.01 -0.0849926 -0.0720879 0.0126994 -0.0840439 -0.0709692 0.01 -0.087891 -0.066145 0.01 -0.0880645 -0.0683012 0.0126994 -0.0897116 -0.063654 0.01 -0.0909087 -0.0644673 0.0126994 -0.0935298 -0.0606018 0.0126994 -0.0949794 -0.061541 0.0155526 -0.0931395 -0.0585238 0.01 -0.0959339 -0.0567195 0.0126994 -0.0914614 -0.061113 0.01 -0.0962744 -0.0532093 0.01 -0.0981274 -0.0528339 0.0126994 -0.0974207 -0.0575986 0.0155526 -0.0996482 -0.0536527 0.0155526 -0.1014 -0.0545959 0.0185002 -0.10167 -0.0497159 0.0155526 -0.100118 -0.0489572 0.0126994 -0.0977288 -0.0504884 0.01 -0.0991065 -0.0477275 0.01 -0.101913 -0.0451006 0.0126994 -0.106975 -0.0426506 0.0185002 -0.105127 -0.0419138 0.0155526 -0.108453 -0.0387368 0.0185002 -0.100406 -0.0449289 0.01 -0.101627 -0.0420955 0.01 -0.103522 -0.0412741 0.0126994 -0.102767 -0.0392287 0.01 -0.104953 -0.0374866 0.0126994 -0.106215 -0.033746 0.0126994 -0.103827 -0.0363309 0.01 -0.104805 -0.0334045 0.01 -0.107317 -0.0300591 0.0126994 -0.105701 -0.0304523 0.01 -0.107861 -0.034269 0.0155526 -0.110896 -0.0310616 0.0185002 -0.109757 -0.0348715 0.0185002 -0.106513 -0.0274758 0.01 -0.108267 -0.0264318 0.0126994 -0.109945 -0.0268414 0.0155526 -0.110766 -0.0232234 0.0155526 -0.112713 -0.0236317 0.0185002 -0.107242 -0.0244774 0.01 -0.10975 -0.0193749 0.0126994 -0.109075 -0.022869 0.0126994 -0.107886 -0.0214601 0.01 -0.108446 -0.0184261 0.01 -0.111451 -0.0196752 0.0155526 -0.110299 -0.015953 0.0126994 -0.10892 -0.0153772 0.01 -0.110732 -0.0126059 0.0126994 -0.109308 -0.0123162 0.01 -0.116644 -0.013279 0.021483 -0.114425 -0.0130263 0.0185002 -0.116985 -0.00983423 0.021483 -0.109611 -0.00924585 0.01 -0.111055 -0.00933575 0.0126994 -0.109827 -0.00616814 0.01 -0.117354 -0.0031939 0.021483 -0.118435 0 0.0227693 -0.119813 -0.00326083 0.0244418 -0.109957 -0.00308534 0.01 -0.111277 -0.00614412 0.0126994 -0.111406 -0.00303201 0.0126994 -0.111448 0 0.0127028 -0.113032 0 0.0153293 -0.0947443 -0.0558884 0.01 -0.0923176 -0.0654664 0.0155526 -0.0939405 -0.0666173 0.0185002 -0.0894293 -0.0693597 0.0155526 -0.0829555 -0.0769855 0.0155526 -0.0863099 -0.0732051 0.0155526 -0.0793642 -0.0806827 0.0155526 -0.0755354 -0.084278 0.0155526 -0.0756911 -0.0929341 0.0244418 -0.0773763 -0.0950033 0.0273172 -0.104016 -0.0965303 0.0395028 -0.10142 -0.0941215 0.0383714 -0.108222 -0.0917902 0.0395028 -0.0970298 -0.0986418 0.0383714 -0.133684 -0.094801 0.0352405 -0.137538 -0.0891168 0.0352405 -0.14042 -0.0909836 0.0328772 -0.120852 -0.0937302 0.039724 -0.127784 -0.0906172 0.0387046 -0.136484 -0.0967869 0.0328772 -0.14315 -0.0927528 0.0301473 -0.123786 -0.0960064 0.0387046 -0.130772 -0.0927362 0.0371966 -0.153936 -0.0910126 0.0201657 -0.148016 -0.0959054 0.0237508 -0.15182 -0.0897614 0.0237508 -0.146829 -0.0868108 0.0301473 -0.144029 -0.0851549 0.0328772 -0.162543 -0.0794828 0.0163769 -0.157456 -0.0847776 0.0201657 -0.16065 -0.078557 0.0201657 -0.159312 -0.0857767 0.0163769 -0.169175 -0.0748662 3.45529e-17 -0.168923 -0.0747547 -0.00419604 -0.168923 -0.0747547 0.00419604 -0.171845 -0.0685143 3.31663e-17 -0.134543 -0.0871758 0.0371966 -0.168193 -0.0744319 0.00835136 -0.171589 -0.0684123 0.00419604 -0.167025 -0.073915 -0.0124252 -0.164083 -0.0802356 -0.0124252 -0.16523 -0.0807966 -0.00835136 -0.172007 -0.0614366 -0.0124252 -0.169662 -0.0676438 -0.0124252 -0.168409 -0.0601513 -0.0201657 -0.166113 -0.0662287 -0.0201657 -0.16807 -0.0670092 -0.0163769 -0.170393 -0.0608602 -0.0163769 -0.172442 -0.0547872 -0.0163769 -0.110985 -0.094134 0.0401362 -0.129501 -0.100439 0.0352405 -0.122262 -0.103699 0.0371966 -0.126681 -0.0982514 0.0371966 -0.170433 -0.0541491 -0.0201657 -0.166094 -0.0593244 -0.0237508 -0.16809 -0.0534047 -0.0237508 -0.114997 -0.0891893 0.0401362 -0.16717 -0.0468239 -0.0270916 -0.165454 -0.0525671 -0.0270916 -0.106672 -0.0989952 0.0401362 -0.164251 -0.0460063 -0.0301473 -0.162565 -0.0516492 -0.0301473 -0.165706 -0.0404546 -0.0301473 -0.162545 -0.0396829 -0.0328772 -0.0964634 -0.0895212 0.0348514 -0.102897 -0.0872742 0.0368012 -0.155742 -0.0380221 -0.0371966 -0.156905 -0.032897 -0.0371966 -0.15332 -0.0321454 -0.0387046 -0.15921 -0.0388687 -0.0352405 -0.161118 -0.0451288 -0.0328772 -0.149685 -0.0313832 -0.039724 -0.152184 -0.0371533 -0.0387046 -0.142212 -0.0451829 -0.0402139 -0.143687 -0.0402465 -0.0402139 -0.140137 -0.0392519 -0.0401362 -0.143314 -0.0253002 -0.0401362 -0.146042 -0.0306195 -0.0402139 -0.146945 -0.0259413 -0.0402139 -0.142433 -0.0298628 -0.0401362 -0.139746 -0.0246702 -0.0395028 -0.119499 -0.0379666 -0.0300502 -0.117986 -0.0330474 -0.0273172 -0.116774 -0.0371009 -0.0273172 -0.13694 -0.0198062 -0.0383714 -0.140445 -0.0203131 -0.0395028 -0.137477 -0.0156507 -0.0383714 -0.127593 -0.0145254 -0.0325813 -0.130758 -0.0148857 -0.0348514 -0.127965 -0.0107573 -0.0325813 -0.130247 -0.0188381 -0.0348514 -0.133535 -0.0193137 -0.0368012 -0.122096 -0.0102639 -0.0273172 -0.12174 -0.0138591 -0.0273172 -0.124581 -0.0141825 -0.0300502 -0.124945 -0.0105034 -0.0300502 -0.118435 0 -0.0227696 -0.117354 -0.0031939 -0.021483 -0.119813 -0.00326083 -0.0244418 -0.119437 -0.0100403 -0.0244418 -0.114425 -0.0130263 -0.0185002 -0.114759 -0.0096471 -0.0185002 -0.112776 -0.00948044 -0.0155526 -0.115121 -0.00313313 -0.0185002 -0.116532 0 -0.0203643 -0.109827 -0.00616737 -0.01 -0.111277 -0.00614412 -0.0126994 -0.109957 -0.00308534 -0.01 -0.113002 -0.00623934 -0.0155526 -0.113132 -0.003079 -0.0155526 -0.111406 -0.00303201 -0.0126994 -0.0532089 -0.0962747 0.01 -0.134059 -0.0152615 -0.0368012 -0.148576 -0.0362725 -0.039724 -0.157812 -0.0442028 -0.0352405 -0.087835 -0.0980012 0.0348514 -0.0857087 -0.0956289 0.0325813 -0.0836855 -0.0933715 0.0300502 -0.0791818 -0.09722 0.0300502 0.00924585 -0.109611 0.01 0.00616814 -0.109827 0.01 -0.0449288 -0.100406 0.01 -0.0375874 -0.108857 0.0185002 -0.03183 -0.110678 0.0185002 -0.0312801 -0.108766 0.0155526 -0.0424464 -0.104913 0.0155526 -0.0254931 -0.110266 0.0155526 -0.00924536 -0.109611 0.01 -0.012316 -0.109308 0.01 -0.00758704 -0.11292 0.0155526 0.0153772 -0.10892 0.01 0.0106104 -0.112676 0.0155526 0.0166197 -0.111947 0.0155526 0.0229547 -0.112853 0.0185002 0.0289007 -0.111478 0.0185002 0.0284014 -0.109552 0.0155526 0.0341265 -0.107906 0.0155526 0.0397121 -0.105978 0.0155526 0.0451387 -0.103783 0.0155526 0.0564216 -0.100396 0.0185002 0.0512745 -0.103119 0.0185002 0.0504884 -0.0977288 0.01 0.0585238 -0.0931395 0.01 0.063654 -0.0897116 0.01 0.077782 -0.0777815 0.01 0.0799505 -0.0776423 0.0126994 0.0649372 -0.0926906 0.0155526 0.0685842 -0.0860012 0.01 0.076297 -0.0812353 0.0126994 0.0755698 -0.0799325 0.01 0.0693501 -0.0894369 0.0155526 0.0735322 -0.0860314 0.0155526 0.0878988 -0.0712895 0.0155526 0.0861505 -0.0764248 0.0185002 0.089444 -0.0725427 0.0185002 0.0878913 -0.0661447 0.01 0.0936764 -0.0635068 0.0155526 0.0909021 -0.067418 0.0155526 0.0931399 -0.0585232 0.01 0.0962272 -0.0595711 0.0155526 0.0985607 -0.0556253 0.0155526 0.10104 -0.0470257 0.0126994 0.105875 -0.0399852 0.0155526 0.104333 -0.0438522 0.0155526 0.105605 -0.03561 0.0126994 0.104805 -0.0334044 0.01 0.108688 -0.024642 0.0126994 0.11053 -0.0142699 0.0126994 0.107242 -0.0244771 0.01 0.10892 -0.0153766 0.01 -0.11473 0 0.0178831 -0.113132 -0.003079 0.0155526 -0.124739 0 0.029462 -0.122481 -0.00333343 0.0273172 -0.122537 0 0.0273276 -0.115121 -0.00313313 0.0185002 -0.113002 -0.00623934 0.0155526 -0.112776 -0.00948044 0.0155526 -0.112448 -0.0128012 0.0155526 -0.112009 -0.0162002 0.0155526 -0.119089 -0.0135572 0.0244418 -0.118623 -0.0171569 0.0244418 -0.116189 -0.0168048 0.021483 -0.10898 -0.030525 0.0155526 -0.10658 -0.0380676 0.0155526 -0.103493 -0.0457995 0.0155526 -0.105312 -0.0466047 0.0185002 -0.10905 -0.0434779 0.021483 -0.107355 -0.0475087 0.021483 -0.0966491 -0.0626229 0.0185002 -0.0991333 -0.0586111 0.0185002 -0.101056 -0.059748 0.021483 -0.0878271 -0.0744921 0.0185002 -0.0927667 -0.0719481 0.021483 -0.0895308 -0.075937 0.021483 -0.0844138 -0.0783388 0.0185002 -0.0807594 -0.0821011 0.0185002 -0.0637474 -0.0959111 0.0185002 -0.0589176 -0.0989515 0.0185002 -0.0538733 -0.101786 0.0185002 -0.0486269 -0.104394 0.0185002 -0.0440305 -0.108828 0.021483 -0.0383165 -0.110969 0.021483 -0.036938 -0.106976 0.0155526 -0.0259413 -0.112204 0.0185002 -0.0199439 -0.113424 0.0185002 -0.0138618 -0.114326 0.0185002 -0.00772041 -0.114905 0.0185002 -0.00154575 -0.115153 0.0185002 0.00463558 -0.11507 0.0185002 0.0107969 -0.114656 0.0185002 0.0172399 -0.116125 0.021483 0.0233999 -0.115042 0.021483 0.0225581 -0.110903 0.0155526 0.0347264 -0.109803 0.0185002 0.0404102 -0.107841 0.0185002 0.0459322 -0.105607 0.0185002 0.0503887 -0.101338 0.0155526 0.06136 -0.0974558 0.0185002 0.0705692 -0.0910091 0.0185002 0.0673605 -0.0961496 0.021483 0.0719381 -0.0927745 0.021483 0.0748249 -0.0875438 0.0185002 0.0774795 -0.0824943 0.0155526 0.0846622 -0.0751045 0.0155526 0.0925001 -0.0686032 0.0185002 0.0953232 -0.0646232 0.0185002 0.102454 -0.052591 0.0185002 0.102239 -0.0577011 0.021483 0.104442 -0.0536111 0.021483 0.100684 -0.0516824 0.0155526 0.102606 -0.0477545 0.0155526 0.106167 -0.0446231 0.0185002 0.107736 -0.0406881 0.0185002 0.107241 -0.0361619 0.0155526 0.10844 -0.0323898 0.0155526 0.109481 -0.0286753 0.0155526 0.110373 -0.0250239 0.0155526 0.111125 -0.0214403 0.0155526 0.111745 -0.0179283 0.0155526 0.112243 -0.0144911 0.0155526 0.112625 -0.011131 0.0155526 0.112902 -0.00784985 0.0155526 0.113079 -0.00464903 0.0155526 0.113164 -0.00152931 0.0155526 0.113164 0.00152931 0.0155526 0.113079 0.00464903 0.0155526 0.112902 0.00784985 0.0155526 0.112243 0.0144911 0.0155526 0.111745 0.0179283 0.0155526 0.111125 0.0214403 0.0155526 0.112313 0.0254638 0.0185002 0.111406 0.0291794 0.0185002 0.10844 0.0323898 0.0155526 0.109127 0.0367976 0.0185002 0.107736 0.0406881 0.0185002 0.104333 0.0438522 0.0155526 0.102606 0.0477545 0.0155526 0.0985607 0.0556253 0.0155526 0.0925001 0.0686032 0.0185002 0.0971723 0.0658767 0.021483 0.0942944 0.0699339 0.021483 0.089444 0.0725427 0.0185002 0.0846622 0.0751045 0.0155526 0.0788415 0.0839446 0.0185002 0.0748249 0.0875438 0.0185002 0.0693501 0.0894369 0.0155526 0.06136 0.0974558 0.0185002 0.0564216 0.100396 0.0185002 0.0512745 0.103119 0.0185002 0.0468232 0.107656 0.021483 0.0411941 0.109933 0.021483 0.0397121 0.105978 0.0155526 0.0289007 0.111478 0.0185002 0.0229547 0.112853 0.0185002 0.0169119 0.113915 0.0185002 0.0107969 0.114656 0.0185002 0.00463558 0.11507 0.0185002 -0.00154575 0.115153 0.0185002 -0.00772041 0.114905 0.0185002 -0.0138618 0.114326 0.0185002 -0.0203307 0.115624 0.021483 -0.0264445 0.11438 0.021483 -0.0259413 0.112204 0.0185002 -0.03183 0.110678 0.0185002 -0.0529426 0.100027 0.0155526 -0.0578997 0.097242 0.0155526 -0.0626461 0.0942542 0.0155526 -0.0671721 0.091084 0.0155526 -0.0714703 0.0877518 0.0155526 -0.0755354 0.084278 0.0155526 -0.0793642 0.0806827 0.0155526 -0.0829555 0.0769855 0.0155526 -0.0863099 0.0732051 0.0155526 -0.0894293 0.0693597 0.0155526 -0.0923176 0.0654664 0.0155526 -0.0768633 0.0857596 0.0185002 -0.0807594 0.0821011 0.0185002 -0.0974207 0.0575986 0.0155526 -0.0949794 0.061541 0.0155526 -0.0996482 0.0536527 0.0155526 -0.10167 0.0497159 0.0155526 -0.103493 0.0457995 0.0155526 -0.105127 0.0419138 0.0155526 -0.0991333 0.0586111 0.0185002 -0.10658 0.0380676 0.0155526 -0.107861 0.034269 0.0155526 -0.10898 0.030525 0.0155526 -0.109945 0.0268414 0.0155526 -0.109757 0.0348715 0.0185002 -0.108453 0.0387368 0.0185002 -0.111451 0.0196752 0.0155526 -0.112009 0.0162002 0.0155526 -0.112448 0.0128012 0.0155526 -0.11341 0.0200211 0.0185002 -0.112776 0.00948044 0.0155526 -0.113132 0.003079 0.0155526 -0.116532 0 0.0203642 -0.114989 -0.00634903 0.0185002 -0.114759 -0.0096471 0.0185002 -0.113978 -0.016485 0.0185002 -0.11341 -0.0200211 0.0185002 -0.118033 -0.0208371 0.0244418 -0.120661 -0.0213011 0.0273172 -0.117307 -0.0245949 0.0244418 -0.111878 -0.0273133 0.0185002 -0.113047 -0.0316641 0.021483 -0.114048 -0.0278431 0.021483 -0.116438 -0.0284266 0.0244418 -0.112874 -0.0403157 0.0244418 -0.110557 -0.0394882 0.021483 -0.114231 -0.0362928 0.0244418 -0.103457 -0.0505899 0.0185002 -0.103367 -0.0556549 0.021483 -0.105464 -0.0515712 0.021483 -0.107674 -0.052652 0.0244418 -0.0985238 -0.0638376 0.021483 -0.100589 -0.0651754 0.0244418 -0.0957627 -0.0679095 0.021483 -0.0910015 -0.0705791 0.0185002 -0.0860513 -0.0798584 0.021483 -0.091407 -0.0775284 0.0244418 -0.0878546 -0.081532 0.0244418 -0.0823259 -0.0836937 0.021483 -0.064984 -0.0977715 0.021483 -0.0600604 -0.100871 0.021483 -0.0549184 -0.10376 0.021483 -0.0506089 -0.108649 0.0244418 -0.0449532 -0.111109 0.0244418 -0.0431926 -0.106757 0.0185002 -0.0324474 -0.112824 0.021483 -0.0264445 -0.11438 0.021483 -0.0203307 -0.115624 0.021483 -0.0141307 -0.116544 0.021483 -0.00787017 -0.117133 0.021483 -0.00157574 -0.117387 0.021483 0.0047255 -0.117302 0.021483 0.011237 -0.11933 0.0244418 0.0176012 -0.118558 0.0244418 0.0169119 -0.113915 0.0185002 0.0294613 -0.113641 0.021483 0.0354 -0.111933 0.021483 0.0411941 -0.109933 0.021483 0.0478044 -0.109912 0.0244418 0.0533645 -0.107323 0.0244418 0.0522691 -0.10512 0.021483 0.057516 -0.102343 0.021483 0.0625502 -0.0993462 0.021483 0.0660788 -0.09432 0.0185002 0.0762763 -0.0892419 0.021483 0.0803708 -0.0855729 0.021483 0.0842194 -0.081788 0.021483 0.0878216 -0.0779073 0.021483 0.091179 -0.0739499 0.021483 0.0942944 -0.0699339 0.021483 0.0971723 -0.0658767 0.021483 0.0979188 -0.0606183 0.0185002 0.100293 -0.0566031 0.0185002 0.104409 -0.048594 0.0185002 0.111243 -0.0375114 0.021483 0.112128 -0.0423466 0.0244418 0.113575 -0.0382975 0.0244418 0.109127 -0.0367976 0.0185002 0.110347 -0.0329592 0.0185002 0.111406 -0.0291794 0.0185002 0.112313 -0.0254638 0.0185002 0.113078 -0.0218172 0.0185002 0.113709 -0.0182435 0.0185002 0.114216 -0.0147458 0.0185002 0.114605 -0.0113266 0.0185002 0.114886 -0.00798785 0.0185002 0.115066 -0.00473076 0.0185002 0.115153 -0.00155619 0.0185002 0.115153 0.00155619 0.0185002 0.115066 0.00473076 0.0185002 0.116431 0.0150319 0.021483 0.119277 0.0117883 0.0244418 0.118871 0.0153469 0.0244418 0.114216 0.0147458 0.0185002 0.113709 0.0182435 0.0185002 0.113078 0.0218172 0.0185002 0.112487 0.0335985 0.021483 0.115947 0.0303688 0.0244418 0.114844 0.0343026 0.0244418 0.110347 0.0329592 0.0185002 0.112128 0.0423466 0.0244418 0.110495 0.046442 0.0244418 0.108226 0.0454887 0.021483 0.106167 0.0446231 0.0185002 0.106435 0.0495366 0.021483 0.104442 0.0536111 0.021483 0.102239 0.0577011 0.021483 0.0998182 0.0617941 0.021483 0.0953232 0.0646232 0.0185002 0.091179 0.0739499 0.021483 0.0878216 0.0779073 0.021483 0.0842194 0.081788 0.021483 0.0803708 0.0855729 0.021483 0.0778748 0.0911121 0.0244418 0.0734456 0.0947187 0.0244418 0.0719381 0.0927745 0.021483 0.0673605 0.0961496 0.021483 0.0625502 0.0993462 0.021483 0.057516 0.102343 0.021483 0.0522691 0.10512 0.021483 0.0459322 0.105607 0.0185002 0.0354 0.111933 0.021483 0.0294613 0.113641 0.021483 0.0233999 0.115042 0.021483 0.0172399 0.116125 0.021483 0.0110064 0.11688 0.021483 0.0047255 0.117302 0.021483 -0.00157574 0.117387 0.021483 -0.00787017 0.117133 0.021483 -0.0144268 0.118986 0.0244418 -0.0207568 0.118047 0.0244418 -0.0199439 0.113424 0.0185002 -0.0324474 0.112824 0.021483 -0.0383165 0.110969 0.021483 -0.0538733 0.101786 0.0185002 -0.0589176 0.0989515 0.0185002 -0.0637474 0.0959111 0.0185002 -0.068353 0.0926852 0.0185002 -0.0727267 0.0892944 0.0185002 -0.105227 0.0681812 0.0300502 -0.107932 0.0638133 0.0300502 -0.105471 0.0623583 0.0273172 -0.0844138 0.0783388 0.0185002 -0.0878271 0.0744921 0.0185002 -0.0910015 0.0705791 0.0185002 -0.0939405 0.0666173 0.0185002 -0.0783542 0.0874231 0.021483 -0.0966491 0.0626229 0.0185002 -0.1014 0.0545959 0.0185002 -0.103457 0.0505899 0.0185002 -0.105312 0.0466047 0.0185002 -0.106975 0.0426506 0.0185002 -0.101056 0.059748 0.021483 -0.110896 0.0310616 0.0185002 -0.111878 0.0273133 0.0185002 -0.111886 0.0355479 0.021483 -0.110557 0.0394882 0.021483 -0.112713 0.0236317 0.0185002 -0.113978 0.016485 0.0185002 -0.114425 0.0130263 0.0185002 -0.114759 0.0096471 0.0185002 -0.116644 0.013279 0.021483 -0.116985 0.00983423 0.021483 -0.115121 0.00313313 0.0185002 -0.114989 0.00634903 0.0185002 -0.13464 0 0.03665 -0.134875 -0.00367074 0.0368012 -0.131993 0 0.0351024 -0.117219 -0.00647218 0.021483 -0.128369 -0.00349369 0.0325813 -0.129463 0 0.0333698 -0.131554 -0.00358036 0.0348514 -0.11561 -0.0204094 0.021483 -0.114899 -0.02409 0.021483 -0.111886 -0.0355479 0.021483 -0.111335 -0.044389 0.0244418 -0.115387 -0.0412134 0.0273172 -0.113814 -0.0453774 0.0273172 -0.103174 -0.0610002 0.0244418 -0.105533 -0.0568212 0.0244418 -0.107883 -0.0580864 0.0273172 -0.0977695 -0.0693326 0.0244418 -0.0840512 -0.0854476 0.0244418 -0.0898107 -0.0833473 0.0273172 -0.0711391 -0.0964631 0.0244418 -0.0663458 -0.0998205 0.0244418 -0.0613191 -0.102985 0.0244418 -0.0573176 -0.108293 0.0273172 -0.0517357 -0.111068 0.0273172 -0.0495701 -0.106419 0.021483 -0.0391195 -0.113294 0.0244418 -0.0331274 -0.115189 0.0244418 -0.0269987 -0.116777 0.0244418 -0.0207568 -0.118047 0.0244418 -0.0144268 -0.118986 0.0244418 -0.0080351 -0.119588 0.0244418 -0.00160876 -0.119847 0.0244418 0.00493195 -0.122427 0.0273172 0.0114872 -0.121987 0.0273172 0.0110064 -0.11688 0.021483 0.0238903 -0.117453 0.0244418 0.0300787 -0.116022 0.0244418 0.0361419 -0.114279 0.0244418 0.0420574 -0.112237 0.0244418 0.0468232 -0.107656 0.021483 0.0587213 -0.104488 0.0244418 0.063861 -0.101428 0.0244418 0.0687722 -0.0981646 0.0244418 0.0734456 -0.0947187 0.0244418 0.0778748 -0.0911121 0.0244418 0.0820551 -0.0873662 0.0244418 0.0859843 -0.083502 0.0244418 0.0896621 -0.07954 0.0244418 0.0930898 -0.0754996 0.0244418 0.0962705 -0.0713995 0.0244418 0.0992086 -0.0672572 0.0244418 0.0998182 -0.0617941 0.021483 0.104381 -0.0589103 0.0244418 0.10663 -0.0547346 0.0244418 0.106435 -0.0495366 0.021483 0.108226 -0.0454887 0.021483 0.109826 -0.0414774 0.021483 0.112487 -0.0335985 0.021483 0.113567 -0.0297454 0.021483 0.114492 -0.0259578 0.021483 0.115272 -0.0222404 0.021483 0.115915 -0.0185974 0.021483 0.116431 -0.0150319 0.021483 0.116828 -0.0115463 0.021483 0.117115 -0.00814279 0.021483 0.117298 -0.00482252 0.021483 0.117387 -0.00158638 0.021483 0.117387 0.00158638 0.021483 0.117298 0.00482252 0.021483 0.117115 0.00814279 0.021483 0.116828 0.0115463 0.021483 0.115915 0.0185974 0.021483 0.115272 0.0222404 0.021483 0.114492 0.0259578 0.021483 0.113567 0.0297454 0.021483 0.111243 0.0375114 0.021483 0.109826 0.0414774 0.021483 0.108665 0.0505747 0.0244418 0.10663 0.0547346 0.0244418 0.104381 0.0589103 0.0244418 0.10191 0.0630891 0.0244418 0.0992086 0.0672572 0.0244418 0.0962705 0.0713995 0.0244418 0.0930898 0.0754996 0.0244418 0.0896621 0.07954 0.0244418 0.0859843 0.083502 0.0244418 0.0820551 0.0873662 0.0244418 0.0762763 0.0892419 0.021483 0.0687722 0.0981646 0.0244418 0.063861 0.101428 0.0244418 0.0587213 0.104488 0.0244418 0.0545527 0.109712 0.0273172 0.0488688 0.112359 0.0273172 0.0478044 0.109912 0.0244418 0.0420574 0.112237 0.0244418 0.0361419 0.114279 0.0244418 0.0300787 0.116022 0.0244418 0.0238903 0.117453 0.0244418 0.0176012 0.118558 0.0244418 0.011237 0.11933 0.0244418 0.00482453 0.119761 0.0244418 -0.00160876 0.119847 0.0244418 -0.008214 0.122251 0.0273172 -0.014748 0.121636 0.0273172 -0.0141307 0.116544 0.021483 -0.0269987 0.116777 0.0244418 -0.0331274 0.115189 0.0244418 -0.0391195 0.113294 0.0244418 -0.045954 0.113582 0.0273172 -0.0600604 0.100871 0.021483 -0.064984 0.0977715 0.021483 -0.0696789 0.094483 0.021483 -0.0741374 0.0910265 0.021483 -0.0449532 0.111109 0.0244418 -0.0860513 0.0798584 0.021483 -0.0895308 0.075937 0.021483 -0.0927667 0.0719481 0.021483 -0.0957627 0.0679095 0.021483 -0.107674 0.052652 0.0244418 -0.105464 0.0515712 0.021483 -0.105533 0.0568212 0.0244418 -0.0985238 0.0638376 0.021483 -0.103367 0.0556549 0.021483 -0.107355 0.0475087 0.021483 -0.10905 0.0434779 0.021483 -0.103174 0.0610002 0.0244418 -0.113047 0.0316641 0.021483 -0.114048 0.0278431 0.021483 -0.114899 0.02409 0.021483 -0.11561 0.0204094 0.021483 -0.116189 0.0168048 0.021483 -0.118033 0.0208371 0.0244418 -0.119089 0.0135572 0.0244418 -0.119437 0.0100403 0.0244418 -0.117354 0.0031939 0.021483 -0.117219 0.00647218 0.021483 -0.120436 0 0.0250932 -0.119676 -0.00660782 0.0244418 -0.119437 -0.0100403 0.0244418 -0.124581 -0.0141825 0.0300502 -0.127965 -0.0107573 0.0325813 -0.127593 -0.0145254 0.0325813 -0.125684 -0.0263512 0.0325813 -0.121808 -0.0297375 0.0300502 -0.122717 -0.0257292 0.0300502 -0.115416 -0.0323277 0.0244418 -0.119499 -0.0379666 0.0300502 -0.116774 -0.0371009 0.0273172 -0.120739 -0.0338186 0.0300502 -0.109605 -0.0485043 0.0244418 -0.112045 -0.0495842 0.0273172 -0.11647 -0.0464362 0.0300502 -0.11466 -0.0507412 0.0300502 -0.105471 -0.0623583 0.0273172 -0.102828 -0.0666266 0.0273172 -0.105227 -0.0681812 0.0300502 -0.0999463 -0.0708763 0.0273172 -0.0947107 -0.0734559 0.0244418 -0.0968195 -0.0750914 0.0273172 -0.0934422 -0.0792545 0.0273172 -0.072723 -0.0986108 0.0273172 -0.067823 -0.102043 0.0273172 -0.0626843 -0.105278 0.0273172 -0.0560692 -0.105935 0.0244418 -0.045954 -0.113582 0.0273172 -0.0399904 -0.115817 0.0273172 -0.033865 -0.117753 0.0273172 -0.0275998 -0.119377 0.0273172 -0.0212189 -0.120675 0.0273172 -0.014748 -0.121636 0.0273172 -0.008214 -0.122251 0.0273172 -0.00168295 -0.125374 0.0300502 0.00504703 -0.125284 0.0300502 0.00482453 -0.119761 0.0244418 0.0179931 -0.121198 0.0273172 0.0244222 -0.120068 0.0273172 0.0307484 -0.118605 0.0273172 0.0369466 -0.116823 0.0273172 0.043997 -0.117413 0.0300502 0.0500091 -0.114981 0.0300502 0.0488688 -0.112359 0.0273172 0.0545527 -0.109712 0.0273172 0.0600287 -0.106814 0.0273172 0.0668062 -0.106106 0.0300502 0.0719438 -0.102692 0.0300502 0.0703034 -0.10035 0.0273172 0.0750809 -0.0968276 0.0273172 0.0814662 -0.095314 0.0300502 0.0858393 -0.0913953 0.0300502 0.0838821 -0.0893114 0.0273172 0.0878988 -0.0853612 0.0273172 0.0916584 -0.0813109 0.0273172 0.0951624 -0.0771806 0.0273172 0.104179 -0.0644938 0.0273172 0.103784 -0.070359 0.0300502 0.10661 -0.0659987 0.0300502 0.10191 -0.0630891 0.0244418 0.106705 -0.0602219 0.0273172 0.109004 -0.0559533 0.0273172 0.108665 -0.0505747 0.0244418 0.110495 -0.046442 0.0244418 0.114624 -0.0432894 0.0273172 0.116103 -0.0391502 0.0273172 0.114844 -0.0343026 0.0244418 0.115947 -0.0303688 0.0244418 0.116891 -0.0265018 0.0244418 0.117687 -0.0227065 0.0244418 0.118344 -0.0189871 0.0244418 0.118871 -0.0153469 0.0244418 0.119277 -0.0117883 0.0244418 0.119569 -0.00831344 0.0244418 0.119757 -0.00492358 0.0244418 0.119847 -0.00161963 0.0244418 0.119847 0.00161963 0.0244418 0.119757 0.00492358 0.0244418 0.119569 0.00831344 0.0244418 0.120979 0.0194099 0.0273172 0.124353 0.0160546 0.0300502 0.123802 0.0198628 0.0300502 0.118344 0.0189871 0.0244418 0.117687 0.0227065 0.0244418 0.116891 0.0265018 0.0244418 0.118528 0.0310449 0.0273172 0.117401 0.0350664 0.0273172 0.113575 0.0382975 0.0244418 0.114624 0.0432894 0.0273172 0.112955 0.047476 0.0273172 0.111084 0.0517008 0.0273172 0.109004 0.0559533 0.0273172 0.106705 0.0602219 0.0273172 0.104179 0.0644938 0.0273172 0.101418 0.0687547 0.0273172 0.0984139 0.0729892 0.0273172 0.0973829 0.0789815 0.0300502 0.0937971 0.0832082 0.0300502 0.0916584 0.0813109 0.0273172 0.0878988 0.0853612 0.0273172 0.0858393 0.0913953 0.0300502 0.0814662 0.095314 0.0300502 0.0796086 0.0931407 0.0273172 0.0750809 0.0968276 0.0273172 0.0703034 0.10035 0.0273172 0.0652829 0.103686 0.0273172 0.0614294 0.109307 0.0300502 0.0558256 0.112272 0.0300502 0.0533645 0.107323 0.0244418 0.0429938 0.114736 0.0273172 0.0369466 0.116823 0.0273172 0.0307484 0.118605 0.0273172 0.0244222 0.120068 0.0273172 0.0179931 0.121198 0.0273172 0.0114872 0.121987 0.0273172 0.00504703 0.125284 0.0300502 -0.00168295 0.125374 0.0300502 -0.00164458 0.122515 0.0273172 -0.00840566 0.125103 0.0300502 -0.0080351 0.119588 0.0244418 -0.0212189 0.120675 0.0273172 -0.0275998 0.119377 0.0273172 -0.033865 0.117753 0.0273172 -0.0399904 0.115817 0.0273172 -0.0663458 0.0998205 0.0244418 -0.0711391 0.0964631 0.0244418 -0.0756911 0.0929341 0.0244418 -0.0878546 0.081532 0.0244418 -0.091407 0.0775284 0.0244418 -0.0947107 0.0734559 0.0244418 -0.0977695 0.0693326 0.0244418 -0.0859226 0.0873501 0.0273172 -0.0817773 0.0912425 0.0273172 -0.100589 0.0651754 0.0244418 -0.109605 0.0485043 0.0244418 -0.111335 0.044389 0.0244418 -0.112874 0.0403157 0.0244418 -0.114231 0.0362928 0.0244418 -0.115416 0.0323277 0.0244418 -0.116438 0.0284266 0.0244418 -0.115387 0.0412134 0.0273172 -0.116774 0.0371009 0.0273172 -0.117307 0.0245949 0.0244418 -0.118623 0.0171569 0.0244418 -0.120661 0.0213011 0.0273172 -0.12174 0.0138591 0.0273172 -0.122096 0.0102639 0.0273172 -0.119813 0.00326083 0.0244418 -0.119676 0.00660782 0.0244418 -0.125339 -0.00341122 0.0300502 -0.12234 -0.00675494 0.0273172 -0.122096 -0.0102639 0.0273172 -0.12174 -0.0138591 0.0273172 -0.121265 -0.0175389 0.0273172 -0.130758 -0.0148857 0.0348514 -0.130247 -0.0188381 0.0348514 -0.127094 -0.0183821 0.0325813 -0.119919 -0.0251425 0.0273172 -0.119031 -0.0290595 0.0273172 -0.117986 -0.0330474 0.0273172 -0.120934 -0.0431947 0.0325813 -0.118079 -0.042175 0.0300502 -0.122388 -0.0388845 0.0325813 -0.110071 -0.0538242 0.0273172 -0.11264 -0.0550802 0.0300502 -0.107932 -0.0638133 0.0300502 -0.1104 -0.0594417 0.0300502 -0.113069 -0.0608788 0.0325813 -0.102278 -0.0725301 0.0300502 -0.104751 -0.0742836 0.0325813 -0.0990786 -0.0768435 0.0300502 -0.0919063 -0.0852921 0.0300502 -0.0979343 -0.0830646 0.0325813 -0.0744199 -0.100912 0.0300502 -0.0694055 -0.104424 0.0300502 -0.0656978 -0.110339 0.0325813 -0.0600731 -0.113499 0.0325813 -0.058655 -0.11082 0.0300502 -0.0529429 -0.11366 0.0300502 -0.0470263 -0.116233 0.0300502 -0.0409236 -0.118519 0.0300502 -0.0346551 -0.120501 0.0300502 -0.0282438 -0.122163 0.0300502 -0.021714 -0.123491 0.0300502 -0.015457 -0.127483 0.0325813 -0.00860888 -0.128128 0.0325813 -0.00840566 -0.125103 0.0300502 -0.00172364 -0.128405 0.0325813 -0.00164458 -0.122515 0.0273172 0.0117552 -0.124833 0.0300502 0.0184129 -0.124026 0.0300502 0.0249921 -0.122869 0.0300502 0.0314658 -0.121373 0.0300502 0.0378087 -0.119549 0.0300502 0.0429938 -0.114736 0.0273172 0.0558256 -0.112272 0.0300502 0.0614294 -0.109307 0.0300502 0.0652829 -0.103686 0.0273172 0.0768328 -0.0990869 0.0300502 0.0796086 -0.0931407 0.0273172 0.0937971 -0.0832082 0.0300502 0.0921244 -0.0894648 0.0325813 0.0960648 -0.0852198 0.0325813 0.0973829 -0.0789815 0.0300502 0.0984139 -0.0729892 0.0273172 0.101418 -0.0687547 0.0273172 0.113676 -0.0529071 0.0300502 0.114245 -0.0586432 0.0325813 0.116425 -0.0541862 0.0325813 0.111084 -0.0517008 0.0273172 0.112955 -0.047476 0.0273172 0.120141 -0.0358846 0.0300502 0.121685 -0.0410323 0.0325813 0.123045 -0.0367521 0.0325813 0.117401 -0.0350664 0.0273172 0.118528 -0.0310449 0.0273172 0.119494 -0.0270918 0.0273172 0.120308 -0.0232121 0.0273172 0.120979 -0.0194099 0.0273172 0.121518 -0.0156886 0.0273172 0.121932 -0.0120508 0.0273172 0.122231 -0.00849853 0.0273172 0.122423 -0.00503321 0.0273172 0.122515 -0.00165569 0.0273172 0.122515 0.00165569 0.0273172 0.122423 0.00503321 0.0273172 0.122231 0.00849853 0.0273172 0.121932 0.0120508 0.0273172 0.121518 0.0156886 0.0273172 0.120308 0.0232121 0.0273172 0.119494 0.0270918 0.0273172 0.121294 0.0317693 0.0300502 0.120141 0.0358846 0.0300502 0.116103 0.0391502 0.0273172 0.117299 0.0442995 0.0300502 0.11559 0.0485838 0.0300502 0.113676 0.0529071 0.0300502 0.111548 0.0572589 0.0300502 0.109195 0.0616271 0.0300502 0.10661 0.0659987 0.0300502 0.103784 0.070359 0.0300502 0.10071 0.0746923 0.0300502 0.0951624 0.0771806 0.0273172 0.0899498 0.0873529 0.0300502 0.0838821 0.0893114 0.0273172 0.0768328 0.0990869 0.0300502 0.0719438 0.102692 0.0300502 0.0684213 0.108671 0.0325813 0.0629146 0.111949 0.0325813 0.0600287 0.106814 0.0273172 0.0500091 0.114981 0.0300502 0.043997 0.117413 0.0300502 0.0378087 0.119549 0.0300502 0.0314658 0.121373 0.0300502 0.0249921 0.122869 0.0300502 0.0184129 0.124026 0.0300502 0.0120394 0.127851 0.0325813 0.00516905 0.128313 0.0325813 0.00493195 0.122427 0.0273172 -0.0150922 0.124474 0.0300502 -0.021714 0.123491 0.0300502 -0.0282438 0.122163 0.0300502 -0.0346551 0.120501 0.0300502 -0.0470263 0.116233 0.0300502 -0.0419129 0.121384 0.0325813 -0.0481633 0.119043 0.0325813 -0.0529429 0.11366 0.0300502 -0.067823 0.102043 0.0273172 -0.072723 0.0986108 0.0273172 -0.0773763 0.0950033 0.0273172 -0.0898107 0.0833473 0.0273172 -0.0934422 0.0792545 0.0273172 -0.0968195 0.0750914 0.0273172 -0.0999463 0.0708763 0.0273172 -0.0836855 0.0933715 0.0300502 -0.0879275 0.0893882 0.0300502 -0.102828 0.0666266 0.0273172 -0.107883 0.0580864 0.0273172 -0.110071 0.0538242 0.0273172 -0.112045 0.0495842 0.0273172 -0.113814 0.0453774 0.0273172 -0.117986 0.0330474 0.0273172 -0.119031 0.0290595 0.0273172 -0.119499 0.0379666 0.0300502 -0.118079 0.042175 0.0300502 -0.119919 0.0251425 0.0273172 -0.121265 0.0175389 0.0273172 -0.123476 0.0217981 0.0300502 -0.124581 0.0141825 0.0300502 -0.124945 0.0105034 0.0300502 -0.12234 0.00675494 0.0273172 -0.122481 0.00333343 0.0273172 -0.127046 0 0.0314822 -0.125195 -0.00691255 0.0300502 -0.124945 -0.0105034 0.0300502 -0.124094 -0.0179482 0.0300502 -0.123476 -0.0217981 0.0300502 -0.123658 -0.0346362 0.0325813 -0.124753 -0.0304565 0.0325813 -0.127848 -0.0312121 0.0348514 -0.119285 -0.0475588 0.0325813 -0.117432 -0.051968 0.0325813 -0.122245 -0.0487387 0.0348514 -0.120345 -0.0532572 0.0348514 -0.107771 -0.0698296 0.0325813 -0.110542 -0.0653561 0.0325813 -0.113284 -0.0669775 0.0348514 -0.0956225 -0.0811038 0.0300502 -0.0810961 -0.0995705 0.0325813 -0.0762191 -0.103351 0.0325813 -0.0728469 -0.109602 0.0348514 -0.0673277 -0.113076 0.0348514 -0.064147 -0.107734 0.0300502 -0.0542229 -0.116408 0.0325813 -0.0481633 -0.119043 0.0325813 -0.0419129 -0.121384 0.0325813 -0.035493 -0.123414 0.0325813 -0.0289266 -0.125116 0.0325813 -0.0158405 -0.130646 0.0348514 -0.0227907 -0.129614 0.0348514 -0.0150922 -0.124474 0.0300502 0.00516905 -0.128313 0.0325813 0.0120394 -0.127851 0.0325813 0.0188581 -0.127025 0.0325813 0.0255963 -0.12584 0.0325813 0.0322266 -0.124307 0.0325813 0.0450607 -0.120251 0.0325813 0.0396834 -0.125477 0.0348514 0.0461785 -0.123235 0.0348514 0.0512181 -0.117761 0.0325813 0.0571752 -0.114986 0.0325813 0.0629146 -0.111949 0.0325813 0.0684213 -0.108671 0.0325813 0.0736831 -0.105174 0.0325813 0.0786903 -0.101482 0.0325813 0.0834358 -0.0976183 0.0325813 0.0879146 -0.0936049 0.0325813 0.0899498 -0.0873529 0.0300502 0.103145 -0.0764981 0.0325813 0.102212 -0.0828977 0.0348514 0.105704 -0.0783959 0.0348514 0.10071 -0.0746923 0.0300502 0.106293 -0.07206 0.0325813 0.109187 -0.0675943 0.0325813 0.109195 -0.0616271 0.0300502 0.111548 -0.0572589 0.0300502 0.11559 -0.0485838 0.0300502 0.117299 -0.0442995 0.0300502 0.118812 -0.0400637 0.0300502 0.121294 -0.0317693 0.0300502 0.122282 -0.027724 0.0300502 0.123115 -0.0237537 0.0300502 0.123802 -0.0198628 0.0300502 0.124353 -0.0160546 0.0300502 0.124777 -0.012332 0.0300502 0.125083 -0.00869683 0.0300502 0.12528 -0.00515065 0.0300502 0.125374 -0.00169432 0.0300502 0.125374 0.00169432 0.0300502 0.12528 0.00515065 0.0300502 0.125083 0.00869683 0.0300502 0.124777 0.012332 0.0300502 0.126091 0.024328 0.0325813 0.129941 0.0208477 0.0348514 0.129219 0.0249315 0.0348514 0.123115 0.0237537 0.0300502 0.122282 0.027724 0.0300502 0.121685 0.0410323 0.0325813 0.126098 0.0376639 0.0348514 0.124704 0.0420502 0.0348514 0.118812 0.0400637 0.0300502 0.120135 0.0453705 0.0325813 0.118385 0.0497584 0.0325813 0.111835 0.063117 0.0325813 0.117079 0.060098 0.0348514 0.11461 0.0646828 0.0348514 0.106293 0.07206 0.0325813 0.111896 0.0692712 0.0348514 0.10893 0.0738477 0.0348514 0.103145 0.0764981 0.0325813 0.0997372 0.080891 0.0325813 0.0960648 0.0852198 0.0325813 0.0921244 0.0894648 0.0325813 0.0879146 0.0936049 0.0325813 0.0834358 0.0976183 0.0325813 0.0786903 0.101482 0.0325813 0.0736831 0.105174 0.0325813 0.0668062 0.106106 0.0300502 0.0571752 0.114986 0.0325813 0.0512181 0.117761 0.0325813 0.0450607 0.120251 0.0325813 0.0387228 0.122439 0.0325813 0.0322266 0.124307 0.0325813 0.0255963 0.12584 0.0325813 0.0193259 0.130176 0.0348514 0.0123381 0.131023 0.0348514 0.0117552 0.124833 0.0300502 -0.00172364 0.128405 0.0325813 -0.00860888 0.128128 0.0325813 -0.015457 0.127483 0.0325813 -0.022239 0.126476 0.0325813 -0.0289266 0.125116 0.0325813 -0.035493 0.123414 0.0325813 -0.0409236 0.118519 0.0300502 -0.0542229 0.116408 0.0325813 -0.0744199 0.100912 0.0300502 -0.0791818 0.09722 0.0300502 -0.0919063 0.0852921 0.0300502 -0.0956225 0.0811038 0.0300502 -0.0900532 0.0915493 0.0325813 -0.0857087 0.0956289 0.0325813 -0.113284 0.0669775 0.0348514 -0.116144 0.0686683 0.0368012 -0.115874 0.0623891 0.0348514 -0.1104 0.0594417 0.0300502 -0.11264 0.0550802 0.0300502 -0.11466 0.0507412 0.0300502 -0.11647 0.0464362 0.0300502 -0.110542 0.0653561 0.0325813 -0.120739 0.0338186 0.0300502 -0.121808 0.0297375 0.0300502 -0.122388 0.0388845 0.0325813 -0.120934 0.0431947 0.0325813 -0.122717 0.0257292 0.0300502 -0.124094 0.0179482 0.0300502 -0.127593 0.0145254 0.0325813 -0.127965 0.0107573 0.0325813 -0.125195 0.00691255 0.0300502 -0.125339 0.00341122 0.0300502 -0.149162 -0.00405959 0.0402139 -0.149355 0 0.040206 -0.152398 0 0.0398302 -0.128221 -0.00707967 0.0325813 -0.141854 -0.00386068 0.0395028 -0.14325 0 0.0398001 -0.145476 -0.00395927 0.0401362 -0.126461 -0.0223251 0.0325813 -0.13287 -0.0234565 0.0368012 -0.128802 -0.0270049 0.0348514 -0.129599 -0.0228789 0.0348514 -0.128591 -0.0408551 0.0368012 -0.125424 -0.0398491 0.0348514 -0.129924 -0.0363915 0.0368012 -0.123934 -0.0442662 0.0348514 -0.127063 -0.0453837 0.0368012 -0.115363 -0.0564118 0.0325813 -0.121209 -0.0592707 0.0368012 -0.115874 -0.0623891 0.0348514 -0.118225 -0.0578113 0.0348514 -0.110445 -0.0715619 0.0348514 -0.113233 -0.0733684 0.0368012 -0.10735 -0.0761264 0.0348514 -0.101474 -0.0787013 0.0325813 -0.103991 -0.0806538 0.0348514 -0.100364 -0.0851253 0.0348514 -0.105521 -0.0894997 0.0383714 -0.083108 -0.102041 0.0348514 -0.0781099 -0.105915 0.0348514 -0.0710835 -0.106949 0.0325813 -0.0615634 -0.116315 0.0348514 -0.055568 -0.119296 0.0348514 -0.0493581 -0.121996 0.0348514 -0.0429527 -0.124396 0.0348514 -0.0363735 -0.126476 0.0348514 -0.023366 -0.132886 0.0368012 -0.0303926 -0.131457 0.0368012 -0.022239 -0.126476 0.0325813 -0.00882245 -0.131306 0.0348514 -0.0017664 -0.131591 0.0348514 0.00529728 -0.131496 0.0348514 0.0123381 -0.131023 0.0348514 0.0193259 -0.130176 0.0348514 0.0262313 -0.128962 0.0348514 0.0406852 -0.128644 0.0368012 0.0338598 -0.130607 0.0368012 0.0387228 -0.122439 0.0325813 0.0524887 -0.120682 0.0348514 0.0585936 -0.117839 0.0348514 0.0718888 -0.114178 0.0368012 0.0701187 -0.111367 0.0348514 0.066103 -0.117623 0.0368012 0.0755111 -0.107784 0.0348514 0.0806425 -0.104 0.0348514 0.0855057 -0.10004 0.0348514 0.0900956 -0.0959271 0.0348514 0.0944099 -0.0916843 0.0348514 0.098448 -0.087334 0.0348514 0.0997372 -0.080891 0.0325813 0.10893 -0.0738477 0.0348514 0.111896 -0.0692712 0.0348514 0.111835 -0.063117 0.0325813 0.117079 -0.060098 0.0348514 0.119313 -0.0555305 0.0348514 0.118385 -0.0497584 0.0325813 0.120135 -0.0453705 0.0325813 0.127308 -0.0333446 0.0348514 0.129281 -0.0386147 0.0368012 0.130522 -0.0341863 0.0368012 0.124226 -0.0325374 0.0325813 0.125238 -0.0283942 0.0325813 0.126091 -0.024328 0.0325813 0.126795 -0.020343 0.0325813 0.12736 -0.0164428 0.0325813 0.127794 -0.0126301 0.0325813 0.128107 -0.00890709 0.0325813 0.128308 -0.00527517 0.0325813 0.128405 -0.00173528 0.0325813 0.128405 0.00173528 0.0325813 0.128308 0.00527517 0.0325813 0.128107 0.00890709 0.0325813 0.127794 0.0126301 0.0325813 0.12736 0.0164428 0.0325813 0.126795 0.020343 0.0325813 0.125238 0.0283942 0.0325813 0.124226 0.0325374 0.0325813 0.123045 0.0367521 0.0325813 0.119313 0.0555305 0.0348514 0.124384 0.0522801 0.0368012 0.122325 0.0569323 0.0368012 0.116425 0.0541862 0.0325813 0.114245 0.0586432 0.0325813 0.109187 0.0675943 0.0325813 0.104792 0.0849904 0.0368012 0.102212 0.0828977 0.0348514 0.108372 0.0803749 0.0368012 0.098448 0.087334 0.0348514 0.09237 0.0983487 0.0368012 0.0900956 0.0959271 0.0348514 0.0967932 0.0939988 0.0368012 0.0855057 0.10004 0.0348514 0.0806425 0.104 0.0348514 0.0718888 0.114178 0.0368012 0.0701187 0.111367 0.0348514 0.0774173 0.110505 0.0368012 0.0644754 0.114726 0.0348514 0.0585936 0.117839 0.0348514 0.0524887 0.120682 0.0348514 0.0461785 0.123235 0.0348514 0.0396834 0.125477 0.0348514 0.0268935 0.132217 0.0368012 0.0262313 0.128962 0.0348514 0.0338598 0.130607 0.0368012 0.0198138 0.133462 0.0368012 0.0188581 0.127025 0.0325813 0.00529728 0.131496 0.0348514 -0.0017664 0.131591 0.0348514 -0.00882245 0.131306 0.0348514 -0.0158405 0.130646 0.0348514 -0.0227907 0.129614 0.0348514 -0.0296442 0.12822 0.0348514 -0.044037 0.127536 0.0368012 -0.0429527 0.124396 0.0348514 -0.0372917 0.129669 0.0368012 -0.0493581 0.121996 0.0348514 -0.055568 0.119296 0.0348514 -0.0615634 0.116315 0.0348514 -0.0863762 0.117124 0.0401362 -0.0919032 0.11284 0.0401362 -0.0762191 0.103351 0.0325813 -0.0810961 0.0995705 0.0325813 -0.0941282 0.0873541 0.0325813 -0.0979343 0.0830646 0.0325813 -0.094617 0.0961889 0.0368012 -0.0922873 0.0938205 0.0348514 -0.0900523 0.100475 0.0368012 -0.104751 0.0742836 0.0325813 -0.087835 0.0980012 0.0348514 -0.107771 0.0698296 0.0325813 -0.113069 0.0608788 0.0325813 -0.115363 0.0564118 0.0325813 -0.117432 0.051968 0.0325813 -0.119285 0.0475588 0.0325813 -0.123658 0.0346362 0.0325813 -0.124753 0.0304565 0.0325813 -0.125424 0.0398491 0.0348514 -0.123934 0.0442662 0.0348514 -0.126461 0.0223251 0.0325813 -0.127094 0.0183821 0.0325813 -0.129599 0.0228789 0.0348514 -0.125684 0.0263512 0.0325813 -0.130758 0.0148857 0.0348514 -0.13114 0.0110242 0.0348514 -0.128369 0.00349369 0.0325813 -0.128221 0.00707967 0.0325813 -0.131402 -0.00725531 0.0348514 -0.13114 -0.0110242 0.0348514 -0.145018 -0.0121908 0.0401362 -0.144596 -0.016461 0.0401362 -0.140996 -0.0160512 0.0395028 -0.131075 -0.032 0.0368012 -0.132054 -0.0276866 0.0368012 -0.135421 -0.0283927 0.0383714 -0.126725 -0.0354954 0.0348514 -0.125331 -0.049969 0.0368012 -0.130303 -0.046541 0.0383714 -0.128527 -0.0512433 0.0383714 -0.116144 -0.0686683 0.0368012 -0.118799 -0.0639641 0.0368012 -0.121829 -0.0655952 0.0383714 -0.11006 -0.0780482 0.0368012 -0.112866 -0.0800384 0.0383714 -0.106617 -0.0826898 0.0368012 -0.0900523 -0.100475 0.0368012 -0.085206 -0.104617 0.0368012 -0.0765904 -0.115234 0.0383714 -0.0746859 -0.112369 0.0368012 -0.0821238 -0.111358 0.0383714 -0.0690273 -0.115931 0.0368012 -0.0631175 -0.119251 0.0368012 -0.0569708 -0.122307 0.0368012 -0.0506041 -0.125076 0.0368012 -0.044037 -0.127536 0.0368012 -0.0311676 -0.134809 0.0383714 -0.0382427 -0.132975 0.0383714 -0.0296442 -0.12822 0.0348514 -0.0162404 -0.133944 0.0368012 -0.00904517 -0.134621 0.0368012 -0.00181099 -0.134913 0.0368012 0.00543101 -0.134815 0.0368012 0.0126496 -0.13433 0.0368012 0.0198138 -0.133462 0.0368012 0.0268935 -0.132217 0.0368012 0.033026 -0.127391 0.0348514 0.0473443 -0.126346 0.0368012 0.0538138 -0.123729 0.0368012 0.0600728 -0.120814 0.0368012 0.0644754 -0.114726 0.0348514 0.0774173 -0.110505 0.0368012 0.0898996 -0.105181 0.0383714 0.0876642 -0.102565 0.0368012 0.0847866 -0.109344 0.0383714 0.09237 -0.0983487 0.0368012 0.0967932 -0.0939988 0.0368012 0.100933 -0.0895387 0.0368012 0.104792 -0.0849904 0.0368012 0.108372 -0.0803749 0.0368012 0.11168 -0.0757119 0.0368012 0.114721 -0.0710199 0.0368012 0.11461 -0.0646828 0.0348514 0.120034 -0.0616151 0.0368012 0.122325 -0.0569323 0.0368012 0.121322 -0.0509928 0.0348514 0.123115 -0.0464961 0.0348514 0.124704 -0.0420502 0.0348514 0.126098 -0.0376639 0.0348514 0.128345 -0.0290986 0.0348514 0.129219 -0.0249315 0.0348514 0.129941 -0.0208477 0.0348514 0.130519 -0.0168507 0.0348514 0.130964 -0.0129434 0.0348514 0.131286 -0.00912806 0.0348514 0.131491 -0.00540604 0.0348514 0.131591 -0.00177833 0.0348514 0.131591 0.00177833 0.0348514 0.131491 0.00540604 0.0348514 0.131286 0.00912806 0.0348514 0.130964 0.0129434 0.0348514 0.130519 0.0168507 0.0348514 0.133221 0.0213739 0.0368012 0.132481 0.0255609 0.0368012 0.128345 0.0290986 0.0348514 0.127308 0.0333446 0.0348514 0.129281 0.0386147 0.0368012 0.127852 0.0431118 0.0368012 0.123115 0.0464961 0.0348514 0.121322 0.0509928 0.0348514 0.120034 0.0616151 0.0368012 0.117503 0.0663157 0.0368012 0.114721 0.0710199 0.0368012 0.11168 0.0757119 0.0368012 0.105704 0.0783959 0.0348514 0.100933 0.0895387 0.0368012 0.0944099 0.0916843 0.0348514 0.0876642 0.102565 0.0368012 0.0826783 0.106625 0.0368012 0.0755111 0.107784 0.0348514 0.066103 0.117623 0.0368012 0.0600728 0.120814 0.0368012 0.0538138 0.123729 0.0368012 0.0473443 0.126346 0.0368012 0.0347232 0.133938 0.0383714 0.0417227 0.131925 0.0383714 0.033026 0.127391 0.0348514 0.0126496 0.13433 0.0368012 0.00543101 0.134815 0.0368012 -0.00181099 0.134913 0.0368012 -0.00904517 0.134621 0.0368012 -0.0162404 0.133944 0.0368012 -0.023366 0.132886 0.0368012 -0.0382427 0.132975 0.0383714 -0.0311676 0.134809 0.0383714 -0.0363735 0.126476 0.0348514 -0.0506041 0.125076 0.0368012 -0.0569708 0.122307 0.0368012 -0.0707875 0.118887 0.0383714 -0.064727 0.122292 0.0383714 -0.083108 0.102041 0.0348514 -0.0964634 0.0895212 0.0348514 -0.10735 0.0761264 0.0348514 -0.130303 0.046541 0.0383714 -0.133638 0.0477321 0.0395028 -0.13187 0.0418969 0.0383714 -0.110445 0.0715619 0.0348514 -0.118225 0.0578113 0.0348514 -0.120345 0.0532572 0.0348514 -0.122245 0.0487387 0.0348514 -0.126725 0.0354954 0.0348514 -0.127848 0.0312121 0.0348514 -0.127063 0.0453837 0.0368012 -0.128591 0.0408551 0.0368012 -0.128802 0.0270049 0.0348514 -0.130247 0.0188381 0.0348514 -0.13287 0.0234565 0.0368012 -0.134059 0.0152615 0.0368012 -0.13445 0.0113025 0.0368012 -0.131554 0.00358036 0.0348514 -0.131402 0.00725531 0.0348514 -0.137404 0 0.0379785 -0.138314 -0.00376435 0.0383714 -0.13472 -0.00743846 0.0368012 -0.13445 -0.0113025 0.0368012 -0.134059 -0.0152615 0.0368012 -0.133535 -0.0193137 0.0368012 -0.144031 -0.0208317 0.0401362 -0.140445 -0.0203131 0.0395028 -0.133237 -0.0373195 0.0383714 -0.134418 -0.032816 0.0383714 -0.137858 -0.0336558 0.0395028 -0.135245 -0.0429691 0.0395028 -0.13187 -0.0418969 0.0383714 -0.136647 -0.0382746 0.0395028 -0.123383 -0.0546016 0.0368012 -0.126529 -0.055994 0.0383714 -0.116121 -0.0752393 0.0383714 -0.119105 -0.0704193 0.0383714 -0.122154 -0.0722215 0.0395028 -0.112133 -0.0869686 0.0395028 -0.0923487 -0.103037 0.0383714 -0.0873787 -0.107284 0.0383714 -0.0800817 -0.108589 0.0368012 -0.0707875 -0.118887 0.0383714 -0.064727 -0.122292 0.0383714 -0.0584236 -0.125426 0.0383714 -0.0518945 -0.128265 0.0383714 -0.0392214 -0.136379 0.0395028 -0.0463157 -0.134135 0.0395028 -0.0372917 -0.129669 0.0368012 -0.0239619 -0.136275 0.0383714 -0.0166545 -0.137359 0.0383714 -0.00927582 -0.138054 0.0383714 -0.00185717 -0.138353 0.0383714 0.0055695 -0.138253 0.0383714 0.0129721 -0.137756 0.0383714 0.020319 -0.136865 0.0383714 0.0356118 -0.137365 0.0395028 0.0347232 -0.133938 0.0383714 0.0282851 -0.139059 0.0395028 0.0417227 -0.131925 0.0383714 0.0485516 -0.129567 0.0383714 0.055186 -0.126884 0.0383714 0.0695235 -0.123709 0.0395028 0.0677886 -0.120622 0.0383714 0.0631812 -0.127065 0.0395028 0.073722 -0.11709 0.0383714 0.0793914 -0.113322 0.0383714 0.0826783 -0.106625 0.0368012 0.0947255 -0.100857 0.0383714 0.0992614 -0.0963958 0.0383714 0.103507 -0.0918219 0.0383714 0.107464 -0.0871577 0.0383714 0.111136 -0.0824245 0.0383714 0.123583 -0.0697472 0.0395028 0.120499 -0.0680068 0.0383714 0.120657 -0.0746948 0.0395028 0.117503 -0.0663157 0.0368012 0.127556 -0.0536132 0.0383714 0.128655 -0.0598783 0.0395028 0.130821 -0.0549853 0.0395028 0.124384 -0.0522801 0.0368012 0.126223 -0.0476698 0.0368012 0.127852 -0.0431118 0.0368012 0.132578 -0.0395994 0.0383714 0.13385 -0.0350581 0.0383714 0.131585 -0.0298332 0.0368012 0.132481 -0.0255609 0.0368012 0.133221 -0.0213739 0.0368012 0.133814 -0.0172761 0.0368012 0.134271 -0.0132702 0.0368012 0.1346 -0.00935849 0.0368012 0.134811 -0.00554251 0.0368012 0.134912 -0.00182322 0.0368012 0.134912 0.00182322 0.0368012 0.134811 0.00554251 0.0368012 0.1346 0.00935849 0.0368012 0.134271 0.0132702 0.0368012 0.133814 0.0172761 0.0368012 0.134941 0.030594 0.0383714 0.139337 0.0268835 0.0395028 0.138394 0.0313769 0.0395028 0.131585 0.0298332 0.0368012 0.130522 0.0341863 0.0368012 0.132578 0.0395994 0.0383714 0.131112 0.0442111 0.0383714 0.126223 0.0476698 0.0368012 0.127556 0.0536132 0.0383714 0.125444 0.0583841 0.0383714 0.123095 0.0631863 0.0383714 0.120499 0.0680068 0.0383714 0.117646 0.0728309 0.0383714 0.114528 0.0776426 0.0383714 0.107464 0.0871577 0.0383714 0.111136 0.0824245 0.0383714 0.103507 0.0918219 0.0383714 0.0947255 0.100857 0.0383714 0.0992614 0.0963958 0.0383714 0.0898996 0.105181 0.0383714 0.0814232 0.116223 0.0395028 0.0793914 0.113322 0.0383714 0.0869564 0.112143 0.0395028 0.073722 0.11709 0.0383714 0.0677886 0.120622 0.0383714 0.0616047 0.123894 0.0383714 0.055186 0.126884 0.0383714 0.0427904 0.135301 0.0395028 0.0497941 0.132883 0.0395028 0.0406852 0.128644 0.0368012 0.0275793 0.135589 0.0383714 0.020319 0.136865 0.0383714 0.0129721 0.137756 0.0383714 0.0055695 0.138253 0.0383714 -0.00185717 0.138353 0.0383714 -0.00927582 0.138054 0.0383714 -0.0166545 0.137359 0.0383714 -0.0319652 0.138259 0.0395028 -0.0245751 0.139762 0.0395028 -0.0303926 0.131457 0.0368012 -0.04516 0.130788 0.0383714 -0.0518945 0.128265 0.0383714 -0.0584236 0.125426 0.0383714 -0.0631175 0.119251 0.0368012 -0.085206 0.104617 0.0368012 -0.0988985 0.0917811 0.0368012 -0.128447 0.0759424 0.0402139 -0.106617 0.0826898 0.0368012 -0.11006 0.0780482 0.0368012 -0.0970298 0.0986418 0.0383714 -0.0923487 0.103037 0.0383714 -0.113233 0.0733684 0.0368012 -0.118799 0.0639641 0.0368012 -0.121209 0.0592707 0.0368012 -0.123383 0.0546016 0.0368012 -0.125331 0.049969 0.0368012 -0.119105 0.0704193 0.0383714 -0.129924 0.0363915 0.0368012 -0.131075 0.032 0.0368012 -0.132054 0.0276866 0.0368012 -0.133535 0.0193137 0.0368012 -0.136258 0.0240546 0.0383714 -0.137477 0.0156507 0.0383714 -0.137879 0.0115907 0.0383714 -0.134875 0.00367074 0.0368012 -0.13472 0.00743846 0.0368012 -0.140279 0 0.0390434 -0.138155 -0.00762815 0.0383714 -0.137879 -0.0115907 0.0383714 -0.137477 -0.0156507 0.0383714 -0.13694 -0.0198062 0.0383714 -0.136258 -0.0240546 0.0383714 -0.143314 -0.0253002 0.0401362 -0.138887 -0.0291193 0.0395028 -0.139746 -0.0246702 0.0395028 -0.13705 -0.0489509 0.0401362 -0.133638 -0.0477321 0.0395028 -0.138698 -0.0440663 0.0401362 -0.131816 -0.0525547 0.0395028 -0.135182 -0.0538966 0.0401362 -0.1243 -0.0607821 0.0383714 -0.127481 -0.0623376 0.0395028 -0.119092 -0.0771649 0.0395028 -0.109335 -0.0847984 0.0383714 -0.099513 -0.101166 0.0395028 -0.0947121 -0.105674 0.0395028 -0.0863762 -0.117124 0.0401362 -0.0842256 -0.114208 0.0395028 -0.0919032 -0.11284 0.0401362 -0.0785505 -0.118183 0.0395028 -0.0725991 -0.121929 0.0395028 -0.0663835 -0.125422 0.0395028 -0.0599187 -0.128636 0.0395028 -0.0474984 -0.13756 0.0401362 -0.0545816 -0.134907 0.0401362 -0.04516 -0.130788 0.0383714 -0.0319652 -0.138259 0.0395028 -0.0245751 -0.139762 0.0395028 -0.0170807 -0.140875 0.0395028 -0.00951321 -0.141587 0.0395028 -0.0019047 -0.141894 0.0395028 0.00571204 -0.141791 0.0395028 0.0133041 -0.141281 0.0395028 0.0290073 -0.14261 0.0401362 0.0213712 -0.143952 0.0401362 0.0275793 -0.135589 0.0383714 0.0427904 -0.135301 0.0395028 0.0497941 -0.132883 0.0395028 0.0565984 -0.130131 0.0395028 0.0616047 -0.123894 0.0383714 0.0756087 -0.120086 0.0395028 0.0814232 -0.116223 0.0395028 0.0922003 -0.107873 0.0395028 0.0869564 -0.112143 0.0395028 0.104401 -0.101387 0.0401362 0.101802 -0.0988627 0.0395028 0.0996304 -0.106079 0.0401362 0.106156 -0.0941718 0.0395028 0.110214 -0.0893882 0.0395028 0.11398 -0.0845339 0.0395028 0.114528 -0.0776426 0.0383714 0.117646 -0.0728309 0.0383714 0.123095 -0.0631863 0.0383714 0.125444 -0.0583841 0.0383714 0.129442 -0.0488854 0.0383714 0.131112 -0.0442111 0.0383714 0.142895 -0.02757 0.0401362 0.145524 -0.0329935 0.0402139 0.146515 -0.0282686 0.0402139 0.134941 -0.030594 0.0383714 0.13586 -0.0262127 0.0383714 0.136618 -0.021919 0.0383714 0.137226 -0.0177166 0.0383714 0.137695 -0.0136086 0.0383714 0.138032 -0.00959713 0.0383714 0.138249 -0.00568385 0.0383714 0.138353 -0.00186972 0.0383714 0.138353 0.00186972 0.0383714 0.138249 0.00568385 0.0383714 0.138032 0.00959713 0.0383714 0.137695 0.0136086 0.0383714 0.137226 0.0177166 0.0383714 0.136618 0.021919 0.0383714 0.13586 0.0262127 0.0383714 0.13385 0.0350581 0.0383714 0.136144 0.0514167 0.0401362 0.132755 0.0501365 0.0395028 0.137901 0.0465004 0.0401362 0.129442 0.0488854 0.0383714 0.130821 0.0549853 0.0395028 0.128655 0.0598783 0.0395028 0.126246 0.0648034 0.0395028 0.123583 0.0697472 0.0395028 0.120657 0.0746948 0.0395028 0.117459 0.0796296 0.0395028 0.110214 0.0893882 0.0395028 0.11398 0.0845339 0.0395028 0.104401 0.101387 0.0401362 0.101802 0.0988627 0.0395028 0.108867 0.0965765 0.0401362 0.0971497 0.103438 0.0395028 0.0922003 0.107873 0.0395028 0.0847866 0.109344 0.0383714 0.0756087 0.120086 0.0395028 0.0695235 0.123709 0.0395028 0.0631812 0.127065 0.0395028 0.0510656 0.136276 0.0401362 0.0580436 0.133454 0.0401362 0.0485516 0.129567 0.0383714 0.0356118 0.137365 0.0395028 0.0282851 0.139059 0.0395028 0.020839 0.140368 0.0395028 0.0133041 0.141281 0.0395028 0.00571204 0.141791 0.0395028 -0.0019047 0.141894 0.0395028 -0.00951321 0.141587 0.0395028 -0.0252026 0.143331 0.0401362 -0.0175169 0.144472 0.0401362 -0.0239619 0.136275 0.0383714 -0.0392214 0.136379 0.0395028 -0.0463157 0.134135 0.0395028 -0.0532226 0.131548 0.0395028 -0.0599187 0.128636 0.0395028 -0.0725991 0.121929 0.0395028 -0.0663835 0.125422 0.0395028 -0.0785505 0.118183 0.0395028 -0.10142 0.0941215 0.0383714 -0.105521 0.0894997 0.0383714 -0.109335 0.0847984 0.0383714 -0.112866 0.0800384 0.0383714 -0.099513 0.101166 0.0395028 -0.0947121 0.105674 0.0395028 -0.116121 0.0752393 0.0383714 -0.121829 0.0655952 0.0383714 -0.1243 0.0607821 0.0383714 -0.126529 0.055994 0.0383714 -0.128527 0.0512433 0.0383714 -0.122154 0.0722215 0.0395028 -0.133237 0.0373195 0.0383714 -0.134418 0.032816 0.0383714 -0.135245 0.0429691 0.0395028 -0.135421 0.0283927 0.0383714 -0.13694 0.0198062 0.0383714 -0.140996 0.0160512 0.0395028 -0.141408 0.0118873 0.0395028 -0.138155 0.00762815 0.0383714 -0.138314 0.00376435 0.0383714 -0.16374 0 0.0353308 -0.163825 -0.00445866 0.0352405 -0.161064 0 0.0368279 -0.141691 -0.00782337 0.0395028 -0.141408 -0.0118873 0.0395028 -0.141378 -0.0345152 0.0401362 -0.142433 -0.0298628 0.0401362 -0.146042 -0.0306195 0.0402139 -0.140137 -0.0392519 0.0401362 -0.14496 -0.0353898 0.0402139 -0.129767 -0.057427 0.0395028 -0.133081 -0.0588934 0.0401362 -0.138607 -0.0552623 0.0402139 -0.136453 -0.0603856 0.0402139 -0.124947 -0.0672739 0.0395028 -0.128137 -0.0689917 0.0401362 -0.125273 -0.0740657 0.0401362 -0.128447 -0.0759424 0.0402139 -0.122133 -0.0791353 0.0401362 -0.115755 -0.0820868 0.0395028 -0.118711 -0.0841828 0.0401362 -0.102054 -0.103749 0.0401362 -0.0971305 -0.108373 0.0401362 -0.0896149 -0.11003 0.0395028 -0.0805563 -0.121201 0.0401362 -0.0744529 -0.125043 0.0401362 -0.0680786 -0.128624 0.0401362 -0.0559647 -0.138325 0.0402139 -0.0630058 -0.135263 0.0402139 -0.0532226 -0.131548 0.0395028 -0.0402229 -0.139861 0.0401362 -0.0327814 -0.14179 0.0401362 -0.0252026 -0.143331 0.0401362 -0.0175169 -0.144472 0.0401362 -0.00975612 -0.145203 0.0401362 -0.00195333 -0.145517 0.0401362 0.00585789 -0.145412 0.0401362 0.0219127 -0.1476 0.0402139 0.0139896 -0.14856 0.0402139 0.020839 -0.140368 0.0395028 0.0365212 -0.140873 0.0401362 0.0438831 -0.138756 0.0401362 0.0510656 -0.136276 0.0401362 0.0580436 -0.133454 0.0401362 0.0712987 -0.126868 0.0401362 0.0647945 -0.13031 0.0401362 0.0775393 -0.123153 0.0401362 0.0914365 -0.11792 0.0402139 0.0891768 -0.115006 0.0401362 0.0856182 -0.12221 0.0402139 0.0945546 -0.110627 0.0401362 0.0971497 -0.103438 0.0395028 0.115893 -0.0939936 0.0402139 0.113028 -0.0916707 0.0401362 0.111625 -0.0990236 0.0402139 0.12351 -0.0837322 0.0402139 0.120458 -0.0816629 0.0401362 0.119852 -0.0888891 0.0402139 0.117459 -0.0796296 0.0395028 0.126739 -0.0715282 0.0401362 0.123738 -0.0766021 0.0401362 0.126246 -0.0648034 0.0395028 0.13194 -0.0614072 0.0401362 0.134161 -0.0563893 0.0401362 0.132755 -0.0501365 0.0395028 0.134467 -0.0453426 0.0395028 0.135971 -0.0406128 0.0395028 0.137276 -0.0359553 0.0395028 0.138394 -0.0313769 0.0395028 0.139337 -0.0268835 0.0395028 0.140115 -0.0224799 0.0395028 0.140738 -0.01817 0.0395028 0.141218 -0.0139569 0.0395028 0.141565 -0.00984275 0.0395028 0.141787 -0.00582931 0.0395028 0.141893 -0.00191757 0.0395028 0.141893 0.00191757 0.0395028 0.141787 0.00582931 0.0395028 0.141565 0.00984275 0.0395028 0.141218 0.0139569 0.0395028 0.140738 0.01817 0.0395028 0.140115 0.0224799 0.0395028 0.142895 0.02757 0.0401362 0.141928 0.0321781 0.0401362 0.137276 0.0359553 0.0395028 0.135971 0.0406128 0.0395028 0.134467 0.0453426 0.0395028 0.134161 0.0563893 0.0401362 0.13194 0.0614072 0.0401362 0.126873 0.0785431 0.0402139 0.123738 0.0766021 0.0401362 0.12995 0.0733406 0.0402139 0.120458 0.0816629 0.0401362 0.113028 0.0916707 0.0401362 0.11689 0.0866925 0.0401362 0.106156 0.0941718 0.0395028 0.0996304 0.106079 0.0401362 0.0914365 0.11792 0.0402139 0.0891768 0.115006 0.0401362 0.0969506 0.11343 0.0402139 0.0835023 0.11919 0.0401362 0.0775393 0.123153 0.0401362 0.0712987 0.126868 0.0401362 0.0595143 0.136835 0.0402139 0.0664364 0.133612 0.0402139 0.0565984 0.130131 0.0395028 0.0438831 0.138756 0.0401362 0.0365212 0.140873 0.0401362 0.0290073 0.14261 0.0401362 0.0213712 0.143952 0.0401362 0.0136438 0.144889 0.0401362 0.00585789 0.145412 0.0401362 -0.00195333 0.145517 0.0401362 -0.0179607 0.148133 0.0402139 -0.0100033 0.148882 0.0402139 -0.0170807 0.140875 0.0395028 -0.0327814 0.14179 0.0401362 -0.0402229 0.139861 0.0401362 -0.0474984 0.13756 0.0401362 -0.0698037 0.131884 0.0402139 -0.0680786 0.128624 0.0401362 -0.0744529 0.125043 0.0401362 -0.0805563 0.121201 0.0401362 -0.104016 0.0965303 0.0395028 -0.108222 0.0917902 0.0395028 -0.112133 0.0869686 0.0395028 -0.115755 0.0820868 0.0395028 -0.102054 0.103749 0.0401362 -0.0971305 0.108373 0.0401362 -0.119092 0.0771649 0.0395028 -0.124947 0.0672739 0.0395028 -0.127481 0.0623376 0.0395028 -0.129767 0.057427 0.0395028 -0.131816 0.0525547 0.0395028 -0.125273 0.0740657 0.0401362 -0.142212 0.0451829 0.0402139 -0.138698 0.0440663 0.0401362 -0.140523 0.0501913 0.0402139 -0.136647 0.0382746 0.0395028 -0.137858 0.0336558 0.0395028 -0.13705 0.0489509 0.0401362 -0.139746 0.0246702 0.0395028 -0.138887 0.0291193 0.0395028 -0.140445 0.0203131 0.0395028 -0.143314 0.0253002 0.0401362 -0.144596 0.016461 0.0401362 -0.145018 0.0121908 0.0401362 -0.141854 0.00386068 0.0395028 -0.141691 0.00782337 0.0395028 -0.146289 0 0.0401985 -0.145309 -0.00802313 0.0401362 -0.160257 -0.00436155 0.0371966 -0.156595 -0.00426189 0.0387046 -0.158273 0 0.0381 -0.151958 -0.0172991 0.039724 -0.156103 -0.0131226 0.0387046 -0.155648 -0.0177192 0.0387046 -0.15504 -0.022424 0.0387046 -0.151364 -0.0218924 0.039724 -0.147271 -0.0412503 0.039724 -0.14576 -0.0463099 0.039724 -0.142212 -0.0451829 0.0402139 -0.144028 -0.0514432 0.039724 -0.140523 -0.0501913 0.0402139 -0.130736 -0.0639294 0.0401362 -0.131384 -0.0707399 0.0402139 -0.134049 -0.0655493 0.0402139 -0.137393 -0.0671843 0.039724 -0.125228 -0.0811405 0.0402139 -0.128352 -0.0831643 0.039724 -0.10464 -0.106378 0.0402139 -0.0995917 -0.111119 0.0402139 -0.102076 -0.11389 0.039724 -0.094232 -0.115699 0.0402139 -0.0885649 -0.120092 0.0402139 -0.0825975 -0.124272 0.0402139 -0.0763395 -0.128211 0.0402139 -0.0698037 -0.131884 0.0402139 -0.0715447 -0.135173 0.039724 -0.0614487 -0.13192 0.0401362 -0.0487019 -0.141046 0.0402139 -0.0412421 -0.143405 0.0402139 -0.0336121 -0.145383 0.0402139 -0.0258412 -0.146963 0.0402139 -0.0179607 -0.148133 0.0402139 -0.0100033 -0.148882 0.0402139 -0.00200283 -0.149204 0.0402139 -0.00205279 -0.152926 0.039724 0.00600632 -0.149097 0.0402139 0.00615614 -0.152815 0.039724 0.0136438 -0.144889 0.0401362 0.0297424 -0.146223 0.0402139 0.0374466 -0.144442 0.0402139 0.044995 -0.142272 0.0402139 0.0523595 -0.13973 0.0402139 0.0595143 -0.136835 0.0402139 0.0609988 -0.140248 0.039724 0.0664364 -0.133612 0.0402139 0.0731054 -0.130083 0.0402139 0.0795041 -0.126273 0.0402139 0.0835023 -0.11919 0.0401362 0.0969506 -0.11343 0.0402139 0.107047 -0.103956 0.0402139 0.102155 -0.108767 0.0402139 0.108867 -0.0965765 0.0401362 0.11689 -0.0866925 0.0401362 0.12995 -0.0733406 0.0402139 0.126873 -0.0785431 0.0402139 0.129469 -0.0664581 0.0401362 0.135283 -0.0629632 0.0402139 0.137561 -0.0578182 0.0402139 0.136144 -0.0514167 0.0401362 0.137901 -0.0465004 0.0401362 0.139443 -0.0416498 0.0401362 0.140781 -0.0368734 0.0401362 0.141928 -0.0321781 0.0401362 0.143692 -0.0230539 0.0401362 0.144332 -0.018634 0.0401362 0.144824 -0.0143132 0.0401362 0.145179 -0.0100941 0.0401362 0.145407 -0.00597816 0.0401362 0.145517 -0.00196653 0.0401362 0.145517 0.00196653 0.0401362 0.145407 0.00597816 0.0401362 0.145179 0.0100941 0.0401362 0.144824 0.0143132 0.0401362 0.144332 0.018634 0.0401362 0.143692 0.0230539 0.0401362 0.145524 0.0329935 0.0402139 0.149154 0.0338164 0.039724 0.144348 0.0378077 0.0402139 0.140781 0.0368734 0.0401362 0.139443 0.0416498 0.0401362 0.139594 0.0527196 0.0402139 0.141395 0.0476786 0.0402139 0.135283 0.0629632 0.0402139 0.138657 0.0645337 0.039724 0.13275 0.0681421 0.0402139 0.129469 0.0664581 0.0401362 0.126739 0.0715282 0.0401362 0.12351 0.0837322 0.0402139 0.126591 0.0858207 0.039724 0.119852 0.0888891 0.0402139 0.115893 0.0939936 0.0402139 0.107047 0.103956 0.0402139 0.111625 0.0990236 0.0402139 0.102155 0.108767 0.0402139 0.0945546 0.110627 0.0401362 0.0856182 0.12221 0.0402139 0.0795041 0.126273 0.0402139 0.0731054 0.130083 0.0402139 0.0647945 0.13031 0.0401362 0.0523595 0.13973 0.0402139 0.044995 0.142272 0.0402139 0.0374466 0.144442 0.0402139 0.0297424 0.146223 0.0402139 0.0219127 0.1476 0.0402139 0.0139896 0.14856 0.0402139 0.00600632 0.149097 0.0402139 -0.00200283 0.149204 0.0402139 -0.00205279 0.152926 0.039724 -0.00975612 0.145203 0.0401362 -0.0258412 0.146963 0.0402139 -0.0336121 0.145383 0.0402139 -0.0412421 0.143405 0.0402139 -0.0487019 0.141046 0.0402139 -0.0763395 0.128211 0.0402139 -0.0825975 0.124272 0.0402139 -0.0846577 0.127372 0.039724 -0.0885649 0.120092 0.0402139 -0.106672 0.0989952 0.0401362 -0.110985 0.094134 0.0401362 -0.114997 0.0891893 0.0401362 -0.118711 0.0841828 0.0401362 -0.122133 0.0791353 0.0401362 -0.128137 0.0689917 0.0401362 -0.130736 0.0639294 0.0401362 -0.133081 0.0588934 0.0401362 -0.135182 0.0538966 0.0401362 -0.140137 0.0392519 0.0401362 -0.141378 0.0345152 0.0401362 -0.142433 0.0298628 0.0401362 -0.144031 0.0208317 0.0401362 -0.146945 0.0259413 0.0402139 -0.14826 0.0168781 0.0402139 -0.148693 0.0124997 0.0402139 -0.145476 0.00395927 0.0401362 -0.145309 0.00802313 0.0401362 -0.152883 -0.00416085 0.039724 -0.148991 -0.00822643 0.0402139 -0.148693 -0.0124997 0.0402139 -0.14826 -0.0168781 0.0402139 -0.147681 -0.0213596 0.0402139 -0.146945 -0.0259413 0.0402139 -0.154268 -0.027234 0.0387046 -0.149685 -0.0313832 0.039724 -0.15061 -0.0265883 0.039724 -0.148576 -0.0362725 0.039724 -0.15332 -0.0321454 0.0387046 -0.143687 -0.0402465 0.0402139 -0.142064 -0.0566407 0.039724 -0.147526 -0.0526924 0.0387046 -0.145514 -0.0580162 0.0387046 -0.131651 -0.0778366 0.039724 -0.134661 -0.0725043 0.039724 -0.137931 -0.074265 0.0387046 -0.112103 -0.104035 0.039724 -0.0965824 -0.118585 0.039724 -0.090774 -0.123088 0.039724 -0.0782436 -0.131409 0.039724 -0.0801436 -0.1346 0.0387046 -0.0645773 -0.138637 0.039724 -0.0573606 -0.141775 0.039724 -0.0499167 -0.144564 0.039724 -0.0422708 -0.146982 0.039724 -0.0344505 -0.149009 0.039724 -0.0264858 -0.150629 0.039724 -0.0102528 -0.152595 0.039724 -0.0105018 -0.156301 0.0387046 0.0143385 -0.152266 0.039724 0.0224592 -0.151281 0.039724 0.0304842 -0.14987 0.039724 0.0383806 -0.148045 0.039724 0.0536655 -0.143215 0.039724 0.0549687 -0.146693 0.0387046 0.0680935 -0.136944 0.039724 0.0749288 -0.133327 0.039724 0.0877537 -0.125259 0.039724 0.0937172 -0.120862 0.039724 0.104703 -0.11148 0.039724 0.114409 -0.101494 0.039724 0.122842 -0.0911063 0.039724 0.136061 -0.0698417 0.039724 0.133191 -0.0751699 0.039724 0.136426 -0.0769953 0.0387046 0.13275 -0.0681421 0.0402139 0.140992 -0.0592603 0.039724 0.144416 -0.0606994 0.0387046 0.143076 -0.0540345 0.039724 0.139594 -0.0527196 0.0402139 0.141395 -0.0476786 0.0402139 0.142976 -0.0427052 0.0402139 0.144348 -0.0378077 0.0402139 0.147333 -0.0236381 0.0402139 0.15017 -0.0289737 0.039724 0.147989 -0.0191061 0.0402139 0.148494 -0.0146759 0.0402139 0.148858 -0.0103498 0.0402139 0.149092 -0.00612964 0.0402139 0.149204 -0.00201636 0.0402139 0.149204 0.00201636 0.0402139 0.149092 0.00612964 0.0402139 0.148858 0.0103498 0.0402139 0.148494 0.0146759 0.0402139 0.147989 0.0191061 0.0402139 0.147333 0.0236381 0.0402139 0.146515 0.0282686 0.0402139 0.142976 0.0427052 0.0402139 0.144922 0.0488679 0.039724 0.137561 0.0578182 0.0402139 0.133191 0.0751699 0.039724 0.114409 0.101494 0.039724 0.118783 0.096338 0.039724 0.121668 0.0986774 0.0387046 0.0993688 0.11626 0.039724 0.104703 0.11148 0.039724 0.107245 0.114187 0.0387046 0.0937172 0.120862 0.039724 0.0877537 0.125259 0.039724 0.0680935 0.136944 0.039724 0.0749288 0.133327 0.039724 0.0767484 0.136565 0.0387046 0.0609988 0.140248 0.039724 0.0536655 0.143215 0.039724 0.0461173 0.145821 0.039724 0.0383806 0.148045 0.039724 0.0304842 0.14987 0.039724 0.00615614 0.152815 0.039724 0.0143385 0.152266 0.039724 0.0146867 0.155963 0.0387046 0.00630563 0.156526 0.0387046 -0.0102528 0.152595 0.039724 -0.0184087 0.151827 0.039724 -0.0264858 0.150629 0.039724 -0.0344505 0.149009 0.039724 -0.0422708 0.146982 0.039724 -0.0715447 0.135173 0.039724 -0.090774 0.123088 0.039724 -0.109375 0.101504 0.0402139 -0.113798 0.0965193 0.0402139 -0.117911 0.0914492 0.0402139 -0.121719 0.0863159 0.0402139 -0.125228 0.0811405 0.0402139 -0.134049 0.0655493 0.0402139 -0.136453 0.0603856 0.0402139 -0.138607 0.0552623 0.0402139 -0.14496 0.0353898 0.0402139 -0.143687 0.0402465 0.0402139 -0.147271 0.0412503 0.039724 -0.14576 0.0463099 0.039724 -0.144028 0.0514432 0.039724 -0.146042 0.0306195 0.0402139 -0.147681 0.0213596 0.0402139 -0.15061 0.0265883 0.039724 -0.148991 0.00822643 0.0402139 -0.149162 0.00405959 0.0402139 -0.155379 0 0.0391128 -0.152707 -0.00843162 0.039724 -0.152402 -0.0128115 0.039724 -0.152184 -0.0371533 0.0387046 -0.15279 -0.0485437 0.0371966 -0.149299 -0.0474345 0.0387046 -0.154375 -0.0432401 0.0371966 -0.139857 -0.0618918 0.039724 -0.143253 -0.0633948 0.0387046 -0.148917 -0.0593728 0.0371966 -0.146603 -0.0648772 0.0371966 -0.131469 -0.0851839 0.0387046 -0.134848 -0.0797268 0.0387046 -0.138001 -0.0815911 0.0371966 -0.119468 -0.101329 0.0387046 -0.114825 -0.106562 0.0387046 -0.10725 -0.109032 0.039724 -0.104555 -0.116656 0.0387046 -0.0989277 -0.121464 0.0387046 -0.0929783 -0.126077 0.0387046 -0.0846577 -0.127372 0.039724 -0.0732821 -0.138456 0.0387046 -0.0661455 -0.142004 0.0387046 -0.0587535 -0.145218 0.0387046 -0.0511289 -0.148075 0.0387046 -0.0432973 -0.150551 0.0387046 -0.0188558 -0.155514 0.0387046 -0.027129 -0.154286 0.0387046 -0.0277633 -0.157894 0.0371966 -0.0192967 -0.159151 0.0371966 -0.0184087 -0.151827 0.039724 -0.00210263 -0.156639 0.0387046 0.00630563 -0.156526 0.0387046 0.0146867 -0.155963 0.0387046 0.0230046 -0.154955 0.0387046 0.0312245 -0.15351 0.0387046 0.0393126 -0.15164 0.0387046 0.0461173 -0.145821 0.039724 0.0624801 -0.143654 0.0387046 0.069747 -0.14027 0.0387046 0.0898847 -0.1283 0.0387046 0.0834659 -0.132566 0.0387046 0.0854177 -0.135666 0.0371966 0.0814871 -0.129423 0.039724 0.107245 -0.114187 0.0387046 0.101782 -0.119083 0.0387046 0.104162 -0.121867 0.0371966 0.0993688 -0.11626 0.039724 0.109717 -0.106549 0.039724 0.117188 -0.103958 0.0387046 0.118783 -0.096338 0.039724 0.125825 -0.0933187 0.0387046 0.126591 -0.0858207 0.039724 0.130038 -0.0805022 0.039724 0.138657 -0.0645337 0.039724 0.144922 -0.0488679 0.039724 0.146542 -0.0437704 0.039724 0.147949 -0.0387507 0.039724 0.149154 -0.0338164 0.039724 0.152198 -0.015042 0.039724 0.15168 -0.0195827 0.039724 0.155364 -0.0200582 0.0387046 0.151008 -0.0242277 0.039724 0.15281 -0.00628253 0.039724 0.152925 -0.00206665 0.039724 0.165942 0.0214239 0.0328772 0.169169 0.0218405 0.0301473 0.165206 0.0265056 0.0328772 0.152925 0.00206665 0.039724 0.15281 0.00628253 0.039724 0.152571 0.010608 0.039724 0.152571 -0.010608 0.039724 0.152198 0.015042 0.039724 0.15168 0.0195827 0.039724 0.151008 0.0242277 0.039724 0.15017 0.0289737 0.039724 0.152776 0.0346376 0.0387046 0.147949 0.0387507 0.039724 0.146542 0.0437704 0.039724 0.144416 0.0606994 0.0387046 0.14655 0.0553467 0.0387046 0.149977 0.0566409 0.0371966 0.143076 0.0540345 0.039724 0.140992 0.0592603 0.039724 0.142024 0.0661008 0.0387046 0.136061 0.0698417 0.039724 0.136426 0.0769953 0.0387046 0.130038 0.0805022 0.039724 0.129665 0.0879048 0.0387046 0.122842 0.0911063 0.039724 0.117188 0.103958 0.0387046 0.109717 0.106549 0.039724 0.101782 0.119083 0.0387046 0.095993 0.123797 0.0387046 0.0834659 0.132566 0.0387046 0.0854177 0.135666 0.0371966 0.0814871 0.129423 0.039724 0.069747 0.14027 0.0387046 0.0624801 0.143654 0.0387046 0.0549687 0.146693 0.0387046 0.0472372 0.149362 0.0387046 0.0393126 0.15164 0.0387046 0.0230046 0.154955 0.0387046 0.0235426 0.158578 0.0371966 0.0224592 0.151281 0.039724 -0.00210263 0.156639 0.0387046 -0.0105018 0.156301 0.0387046 -0.0188558 0.155514 0.0387046 -0.027129 0.154286 0.0387046 -0.0352871 0.152627 0.0387046 -0.0587535 0.145218 0.0387046 -0.0511289 0.148075 0.0387046 -0.0523244 0.151537 0.0371966 -0.0499167 0.144564 0.039724 -0.0661455 0.142004 0.0387046 -0.0732821 0.138456 0.0387046 -0.0782436 0.131409 0.039724 -0.0867135 0.130465 0.0387046 -0.0929783 0.126077 0.0387046 -0.120127 0.111482 0.0352405 -0.124984 0.106007 0.0352405 -0.112103 0.104035 0.039724 -0.116636 0.0989267 0.039724 -0.120852 0.0937302 0.039724 -0.124755 0.0884689 0.039724 -0.128352 0.0831643 0.039724 -0.142064 0.0566407 0.039724 -0.143253 0.0633948 0.0387046 -0.145514 0.0580162 0.0387046 -0.137393 0.0671843 0.039724 -0.139857 0.0618918 0.039724 -0.134848 0.0797268 0.0387046 -0.15332 0.0321454 0.0387046 -0.154268 0.027234 0.0387046 -0.148576 0.0362725 0.039724 -0.147526 0.0526924 0.0387046 -0.149299 0.0474345 0.0387046 -0.149685 0.0313832 0.039724 -0.151364 0.0218924 0.039724 -0.151958 0.0172991 0.039724 -0.152402 0.0128115 0.039724 -0.155648 0.0177192 0.0387046 -0.156103 0.0131226 0.0387046 -0.152883 0.00416085 0.039724 -0.152707 0.00843162 0.039724 -0.17102 0 0.02973 -0.17318 0 0.027553 -0.170509 -0.00464057 0.0301473 -0.156415 -0.00863637 0.0387046 -0.167257 -0.00455206 0.0328772 -0.168723 0 0.031762 -0.162834 -0.0185373 0.0352405 -0.159288 -0.0181336 0.0371966 -0.16331 -0.0137285 0.0352405 -0.162198 -0.0234593 0.0352405 -0.158666 -0.0229483 0.0371966 -0.16139 -0.0284914 0.0352405 -0.156905 -0.032897 0.0371966 -0.157875 -0.0278708 0.0371966 -0.163758 -0.034334 0.0328772 -0.15921 -0.0388687 0.0352405 -0.160398 -0.0336295 0.0352405 -0.150848 -0.0422521 0.0387046 -0.154337 -0.0551252 0.0352405 -0.150975 -0.0539245 0.0371966 -0.156192 -0.0496245 0.0352405 -0.140729 -0.0688158 0.0387046 -0.14402 -0.0704249 0.0371966 -0.112423 -0.114291 0.0371966 -0.114926 -0.116836 0.0352405 -0.106999 -0.119384 0.0371966 -0.109854 -0.111679 0.0387046 -0.101241 -0.124305 0.0371966 -0.0887412 -0.133515 0.0371966 -0.090717 -0.136488 0.0352405 -0.0820177 -0.137748 0.0371966 -0.0867135 -0.130465 0.0387046 -0.0749957 -0.141693 0.0371966 -0.0676922 -0.145324 0.0371966 -0.0601274 -0.148614 0.0371966 -0.0523244 -0.151537 0.0371966 -0.0361122 -0.156196 0.0371966 -0.0369163 -0.159674 0.0352405 -0.0352871 -0.152627 0.0387046 -0.0107474 -0.159956 0.0371966 -0.0021518 -0.160302 0.0371966 0.00645308 -0.160187 0.0371966 0.0150301 -0.15961 0.0371966 0.0235426 -0.158578 0.0371966 0.0319546 -0.1571 0.0371966 0.0483418 -0.152854 0.0371966 0.0494182 -0.156258 0.0352405 0.0562541 -0.150123 0.0371966 0.0472372 -0.149362 0.0387046 0.0639411 -0.147013 0.0371966 0.071378 -0.14355 0.0371966 0.0767484 -0.136565 0.0387046 0.0919866 -0.131301 0.0371966 0.095993 -0.123797 0.0387046 0.115009 -0.111689 0.0371966 0.11757 -0.114175 0.0352405 0.119928 -0.106389 0.0371966 0.112381 -0.109137 0.0387046 0.121668 -0.0986774 0.0387046 0.132697 -0.0899603 0.0371966 0.135652 -0.0919633 0.0352405 0.13631 -0.0843852 0.0371966 0.129665 -0.0879048 0.0387046 0.133196 -0.0824571 0.0387046 0.139616 -0.0787958 0.0371966 0.139365 -0.0715378 0.0387046 0.142024 -0.0661008 0.0387046 0.151912 -0.051225 0.0371966 0.149977 -0.0566409 0.0371966 0.153317 -0.0579021 0.0352405 0.14655 -0.0553467 0.0387046 0.148441 -0.0500546 0.0387046 0.150101 -0.0448333 0.0387046 0.151542 -0.0396918 0.0387046 0.152776 -0.0346376 0.0387046 0.153817 -0.0296773 0.0387046 0.154675 -0.024816 0.0387046 0.155894 -0.0154073 0.0387046 0.156276 -0.0108656 0.0387046 0.156521 -0.00643509 0.0387046 0.156639 -0.00211684 0.0387046 0.156639 0.00211684 0.0387046 0.156521 0.00643509 0.0387046 0.156276 0.0108656 0.0387046 0.155894 0.0154073 0.0387046 0.155364 0.0200582 0.0387046 0.154675 0.024816 0.0387046 0.153817 0.0296773 0.0387046 0.155085 0.0406199 0.0371966 0.158538 0.0415243 0.0352405 0.153611 0.0458817 0.0371966 0.151542 0.0396918 0.0387046 0.150101 0.0448333 0.0387046 0.148441 0.0500546 0.0387046 0.145346 0.0676465 0.0371966 0.139365 0.0715378 0.0387046 0.139616 0.0787958 0.0371966 0.133196 0.0824571 0.0387046 0.132697 0.0899603 0.0371966 0.125825 0.0933187 0.0387046 0.124513 0.100985 0.0371966 0.119928 0.106389 0.0371966 0.112381 0.109137 0.0387046 0.109753 0.116857 0.0371966 0.104162 0.121867 0.0371966 0.0919866 0.131301 0.0371966 0.0940347 0.134224 0.0352405 0.0898847 0.1283 0.0387046 0.0785431 0.139758 0.0371966 0.071378 0.14355 0.0371966 0.0639411 0.147013 0.0371966 0.0562541 0.150123 0.0371966 0.0402319 0.155186 0.0371966 0.0411277 0.158642 0.0352405 0.0319546 0.1571 0.0371966 0.0326661 0.160597 0.0352405 0.0312245 0.15351 0.0387046 0.0150301 0.15961 0.0371966 0.00645308 0.160187 0.0371966 -0.0021518 0.160302 0.0371966 -0.0107474 0.159956 0.0371966 -0.0192967 0.159151 0.0371966 -0.0277633 0.157894 0.0371966 -0.0443097 0.154072 0.0371966 -0.0452963 0.157502 0.0352405 -0.0432973 0.150551 0.0387046 -0.0601274 0.148614 0.0371966 -0.0676922 0.145324 0.0371966 -0.0820177 0.137748 0.0371966 -0.0838439 0.140815 0.0352405 -0.0887412 0.133515 0.0371966 -0.0801436 0.1346 0.0387046 -0.101241 0.124305 0.0371966 -0.103495 0.127072 0.0352405 -0.0989277 0.121464 0.0387046 -0.119468 0.101329 0.0387046 -0.123786 0.0960064 0.0387046 -0.127784 0.0906172 0.0387046 -0.131469 0.0851839 0.0387046 -0.137931 0.074265 0.0387046 -0.140729 0.0688158 0.0387046 -0.15279 0.0485437 0.0371966 -0.150848 0.0422521 0.0387046 -0.138001 0.0815911 0.0371966 -0.152184 0.0371533 0.0387046 -0.150975 0.0539245 0.0371966 -0.15504 0.022424 0.0387046 -0.157875 0.0278708 0.0371966 -0.159288 0.0181336 0.0371966 -0.159753 0.0134295 0.0371966 -0.156415 0.00863637 0.0387046 -0.156595 0.00426189 0.0387046 -0.160073 -0.00883832 0.0371966 -0.159753 -0.0134295 0.0371966 -0.155742 -0.0380221 0.0371966 -0.157812 -0.0442028 0.0352405 -0.162545 -0.0396829 0.0328772 -0.152233 -0.0606948 0.0352405 -0.15757 -0.0562799 0.0328772 -0.155421 -0.0619662 0.0328772 -0.149867 -0.0663217 0.0352405 -0.153006 -0.067711 0.0328772 -0.141156 -0.0760016 0.0371966 -0.144299 -0.0776938 0.0352405 -0.141074 -0.0834078 0.0352405 -0.124984 -0.106007 0.0352405 -0.11751 -0.109054 0.0371966 -0.109382 -0.122042 0.0352405 -0.0972711 -0.131898 0.0352405 -0.0993087 -0.13466 0.0328772 -0.0951525 -0.129025 0.0371966 -0.0838439 -0.140815 0.0352405 -0.0766656 -0.144848 0.0352405 -0.0691994 -0.14856 0.0352405 -0.0534895 -0.154911 0.0352405 -0.0546099 -0.158156 0.0328772 -0.0452963 -0.157502 0.0352405 -0.0462451 -0.160801 0.0328772 -0.0443097 -0.154072 0.0371966 -0.0283815 -0.16141 0.0352405 -0.0197263 -0.162694 0.0352405 -0.0109867 -0.163517 0.0352405 -0.00219971 -0.163871 0.0352405 0.00659676 -0.163753 0.0352405 0.0153648 -0.163164 0.0352405 0.0240668 -0.162109 0.0352405 0.0411277 -0.158642 0.0352405 0.0419892 -0.161965 0.0328772 0.0402319 -0.155186 0.0371966 0.0575066 -0.153465 0.0352405 0.0653648 -0.150287 0.0352405 0.0802918 -0.14287 0.0352405 0.0819738 -0.145863 0.0328772 0.0873196 -0.138686 0.0352405 0.0785431 -0.139758 0.0371966 0.0940347 -0.134224 0.0352405 0.0982376 -0.126692 0.0371966 0.106481 -0.124581 0.0352405 0.109753 -0.116857 0.0371966 0.127285 -0.103233 0.0352405 0.129951 -0.105396 0.0328772 0.131634 -0.0976272 0.0352405 0.124513 -0.100985 0.0371966 0.128767 -0.0955008 0.0371966 0.142724 -0.0805502 0.0352405 0.142624 -0.0732106 0.0371966 0.145346 -0.0676465 0.0371966 0.147793 -0.0621188 0.0371966 0.153611 -0.0458817 0.0371966 0.155085 -0.0406199 0.0371966 0.156348 -0.0354476 0.0371966 0.157413 -0.0303712 0.0371966 0.158292 -0.0253963 0.0371966 0.158997 -0.0205273 0.0371966 0.159539 -0.0157675 0.0371966 0.15993 -0.0111197 0.0371966 0.160181 -0.00658557 0.0371966 0.160302 -0.00216634 0.0371966 0.160302 0.00216634 0.0371966 0.160181 0.00658557 0.0371966 0.15993 0.0111197 0.0371966 0.159539 0.0157675 0.0371966 0.158997 0.0205273 0.0371966 0.158292 0.0253963 0.0371966 0.157413 0.0303712 0.0371966 0.156348 0.0354476 0.0371966 0.151912 0.051225 0.0371966 0.153317 0.0579021 0.0352405 0.147793 0.0621188 0.0371966 0.1458 0.0748407 0.0352405 0.148854 0.0764084 0.0328772 0.142724 0.0805502 0.0352405 0.142624 0.0732106 0.0371966 0.139345 0.0862641 0.0352405 0.142264 0.0880711 0.0328772 0.135652 0.0919633 0.0352405 0.13631 0.0843852 0.0371966 0.128767 0.0955008 0.0371966 0.127285 0.103233 0.0352405 0.11757 0.114175 0.0352405 0.120032 0.116567 0.0328772 0.112197 0.119459 0.0352405 0.115009 0.111689 0.0371966 0.106481 0.124581 0.0352405 0.0982376 0.126692 0.0371966 0.0873196 0.138686 0.0352405 0.0802918 0.14287 0.0352405 0.0729673 0.146746 0.0352405 0.0653648 0.150287 0.0352405 0.0494182 0.156258 0.0352405 0.0504533 0.159531 0.0328772 0.0483418 0.152854 0.0371966 0.0240668 0.162109 0.0352405 0.0153648 0.163164 0.0352405 0.00659676 0.163753 0.0352405 -0.00219971 0.163871 0.0352405 -0.0109867 0.163517 0.0352405 -0.0197263 0.162694 0.0352405 -0.0369163 0.159674 0.0352405 -0.0376896 0.163019 0.0328772 -0.0361122 0.156196 0.0371966 -0.0534895 0.154911 0.0352405 -0.0614661 0.151923 0.0352405 -0.0691994 0.14856 0.0352405 -0.0749957 0.141693 0.0371966 -0.090717 0.136488 0.0352405 -0.0951525 0.129025 0.0371966 -0.109382 0.122042 0.0352405 -0.122262 0.103699 0.0371966 -0.126681 0.0982514 0.0371966 -0.130772 0.0927362 0.0371966 -0.134543 0.0871758 0.0371966 -0.141156 0.0760016 0.0371966 -0.146603 0.0648772 0.0371966 -0.148917 0.0593728 0.0371966 -0.141074 0.0834078 0.0352405 -0.159464 0.050664 0.0328772 -0.156192 0.0496245 0.0352405 -0.15757 0.0562799 0.0328772 -0.154375 0.0432401 0.0371966 -0.155742 0.0380221 0.0371966 -0.154337 0.0551252 0.0352405 -0.156905 0.032897 0.0371966 -0.158666 0.0229483 0.0371966 -0.16139 0.0284914 0.0352405 -0.162834 0.0185373 0.0352405 -0.16331 0.0137285 0.0352405 -0.160257 0.00436155 0.0371966 -0.160073 0.00883832 0.0371966 -0.166295 0 0.0336348 -0.163637 -0.00903511 0.0352405 -0.176305 -0.0047983 0.0237508 -0.17354 -0.00472304 0.0270916 -0.175197 0 0.0252429 -0.169478 -0.0192936 0.0301473 -0.172994 -0.0145426 0.0270916 -0.17249 -0.0196365 0.0270916 -0.168816 -0.0244164 0.0301473 -0.165596 -0.0239507 0.0328772 -0.162565 -0.0516492 0.0301473 -0.159464 -0.050664 0.0328772 -0.164251 -0.0460063 0.0301473 -0.147226 -0.071993 0.0352405 -0.147322 -0.0793213 0.0328772 -0.15031 -0.073501 0.0328772 -0.153233 -0.0749303 0.0301473 -0.132214 -0.102543 0.0328772 -0.122643 -0.113817 0.0328772 -0.125028 -0.11603 0.0301473 -0.117334 -0.119283 0.0328772 -0.120127 -0.111482 0.0352405 -0.111673 -0.124598 0.0328772 -0.103495 -0.127072 0.0352405 -0.0926173 -0.139347 0.0328772 -0.0856002 -0.143765 0.0328772 -0.0782715 -0.147882 0.0328772 -0.0627537 -0.155105 0.0328772 -0.063974 -0.158121 0.0301473 -0.0614661 -0.151923 0.0352405 -0.0376896 -0.163019 0.0328772 -0.028976 -0.164791 0.0328772 -0.0201396 -0.166103 0.0328772 -0.0112168 -0.166943 0.0328772 -0.00224579 -0.167304 0.0328772 0.00673495 -0.167183 0.0328772 0.0156866 -0.166582 0.0328772 0.0333504 -0.163962 0.0328772 0.0339989 -0.16715 0.0301473 0.0326661 -0.160597 0.0352405 0.0504533 -0.159531 0.0328772 0.0587112 -0.15668 0.0328772 0.066734 -0.153435 0.0328772 0.0729673 -0.146746 0.0352405 0.0891487 -0.141592 0.0328772 0.102529 -0.132225 0.0328772 0.104522 -0.134797 0.0301473 0.108712 -0.127191 0.0328772 0.100425 -0.129512 0.0352405 0.112197 -0.119459 0.0352405 0.120032 -0.116567 0.0328772 0.122598 -0.108758 0.0352405 0.138493 -0.0938897 0.0328772 0.139345 -0.0862641 0.0352405 0.151694 -0.0706013 0.0328772 0.148854 -0.0764084 0.0328772 0.151748 -0.0778942 0.0301473 0.1458 -0.0748407 0.0352405 0.148582 -0.0691527 0.0352405 0.151083 -0.0635019 0.0352405 0.156528 -0.059115 0.0328772 0.155295 -0.0523656 0.0352405 0.157031 -0.0469032 0.0352405 0.158538 -0.0415243 0.0352405 0.15983 -0.0362368 0.0352405 0.160918 -0.0310475 0.0352405 0.161817 -0.0259618 0.0352405 0.162537 -0.0209843 0.0352405 0.163091 -0.0161186 0.0352405 0.163491 -0.0113673 0.0352405 0.163748 -0.0067322 0.0352405 0.163871 -0.00221457 0.0352405 0.163871 0.00221457 0.0352405 0.163748 0.0067322 0.0352405 0.163491 0.0113673 0.0352405 0.163091 0.0161186 0.0352405 0.162537 0.0209843 0.0352405 0.161817 0.0259618 0.0352405 0.160918 0.0310475 0.0352405 0.15983 0.0362368 0.0352405 0.161859 0.0423942 0.0328772 0.157031 0.0469032 0.0352405 0.155295 0.0523656 0.0352405 0.156528 0.059115 0.0328772 0.151083 0.0635019 0.0352405 0.148582 0.0691527 0.0352405 0.134392 0.0996722 0.0328772 0.137005 0.10161 0.0301473 0.129951 0.105396 0.0328772 0.131634 0.0976272 0.0352405 0.122598 0.108758 0.0352405 0.114547 0.121961 0.0328772 0.102529 0.132225 0.0328772 0.104522 0.134797 0.0301473 0.0960045 0.137036 0.0328772 0.100425 0.129512 0.0352405 0.0891487 0.141592 0.0328772 0.0819738 0.145863 0.0328772 0.0744957 0.14982 0.0328772 0.0587112 0.15668 0.0328772 0.0598529 0.159727 0.0301473 0.0575066 0.153465 0.0352405 0.0419892 0.161965 0.0328772 0.0333504 0.163962 0.0328772 0.0245709 0.165505 0.0328772 0.0156866 0.166582 0.0328772 0.00673495 0.167183 0.0328772 -0.00224579 0.167304 0.0328772 -0.0112168 0.166943 0.0328772 -0.028976 0.164791 0.0328772 -0.0295395 0.167995 0.0301473 -0.0283815 0.16141 0.0352405 -0.0462451 0.160801 0.0328772 -0.0546099 0.158156 0.0328772 -0.0627537 0.155105 0.0328772 -0.0782715 0.147882 0.0328772 -0.0797935 0.150758 0.0301473 -0.0856002 0.143765 0.0328772 -0.0766656 0.144848 0.0352405 -0.0926173 0.139347 0.0328772 -0.0972711 0.131898 0.0352405 -0.105663 0.129734 0.0328772 -0.117334 0.119283 0.0328772 -0.119615 0.121603 0.0301473 -0.129501 0.100439 0.0352405 -0.133684 0.094801 0.0352405 -0.111673 0.124598 0.0328772 -0.137538 0.0891168 0.0352405 -0.144029 0.0851549 0.0328772 -0.149867 0.0663217 0.0352405 -0.152233 0.0606948 0.0352405 -0.157812 0.0442028 0.0352405 -0.15921 0.0388687 0.0352405 -0.160398 0.0336295 0.0352405 -0.162198 0.0234593 0.0352405 -0.166731 0.0140161 0.0328772 -0.163637 0.00903511 0.0352405 -0.166245 0.0189256 0.0328772 -0.163825 0.00445866 0.0352405 -0.178762 -0.00486518 0.0201657 -0.177063 0 0.0228092 -0.178769 0 0.020261 -0.167065 -0.00922437 0.0328772 -0.166731 -0.0140161 0.0328772 -0.166245 -0.0189256 0.0328772 -0.164771 -0.0290882 0.0328772 -0.17096 -0.0301808 0.0270916 -0.166943 -0.0350016 0.0301473 -0.167975 -0.0296538 0.0301473 -0.165706 -0.0404546 0.0301473 -0.16991 -0.0356236 0.0270916 -0.161118 -0.0451288 0.0328772 -0.160634 -0.0573743 0.0301473 -0.158444 -0.0631711 0.0301473 -0.163488 -0.058394 0.0270916 -0.16126 -0.0642938 0.0270916 -0.150187 -0.0808637 0.0301473 -0.134785 -0.104537 0.0301473 -0.127602 -0.108228 0.0328772 -0.119615 -0.121603 0.0301473 -0.10124 -0.137279 0.0301473 -0.107718 -0.132257 0.0301473 -0.109632 -0.134607 0.0270916 -0.105663 -0.129734 0.0328772 -0.0944183 -0.142057 0.0301473 -0.0872647 -0.14656 0.0301473 -0.0720228 -0.154621 0.0301473 -0.0733028 -0.157369 0.0270916 -0.070649 -0.151672 0.0328772 -0.0556719 -0.161232 0.0301473 -0.0471444 -0.163928 0.0301473 -0.0384224 -0.166189 0.0301473 -0.0295395 -0.167995 0.0301473 -0.0205312 -0.169332 0.0301473 -0.0114349 -0.170189 0.0301473 -0.00228946 -0.170557 0.0301473 0.0159917 -0.169821 0.0301473 0.0162759 -0.172839 0.0270916 0.0250487 -0.168723 0.0301473 0.0254939 -0.171722 0.0270916 0.0245709 -0.165505 0.0328772 0.0428057 -0.165114 0.0301473 0.0514344 -0.162633 0.0301473 0.0598529 -0.159727 0.0301473 0.0759443 -0.152733 0.0301473 0.077294 -0.155448 0.0270916 0.0835678 -0.148699 0.0301473 0.0744957 -0.14982 0.0328772 0.0908822 -0.144345 0.0301473 0.0960045 -0.137036 0.0328772 0.110826 -0.129664 0.0301473 0.114547 -0.121961 0.0328772 0.122366 -0.118834 0.0301473 0.125166 -0.111036 0.0328772 0.132478 -0.107445 0.0301473 0.134392 -0.0996722 0.0328772 0.141186 -0.0957154 0.0301473 0.142264 -0.0880711 0.0328772 0.145714 -0.0822375 0.0328772 0.154248 -0.0648321 0.0328772 0.163438 -0.0488169 0.0301473 0.161631 -0.0545021 0.0301473 0.164503 -0.0554707 0.0270916 0.158548 -0.0534625 0.0328772 0.16032 -0.0478857 0.0328772 0.161859 -0.0423942 0.0328772 0.163178 -0.0369959 0.0328772 0.164289 -0.0316978 0.0328772 0.165206 -0.0265056 0.0328772 0.165942 -0.0214239 0.0328772 0.166508 -0.0164563 0.0328772 0.166916 -0.0116054 0.0328772 0.167178 -0.00687322 0.0328772 0.167304 -0.00226096 0.0328772 0.167304 0.00226096 0.0328772 0.167178 0.00687322 0.0328772 0.166916 0.0116054 0.0328772 0.166508 0.0164563 0.0328772 0.164289 0.0316978 0.0328772 0.163178 0.0369959 0.0328772 0.161631 0.0545021 0.0301473 0.163438 0.0488169 0.0301473 0.166342 0.0496845 0.0270916 0.16032 0.0478857 0.0328772 0.158548 0.0534625 0.0328772 0.154644 0.0719741 0.0301473 0.157247 0.0660928 0.0301473 0.160042 0.0672673 0.0270916 0.154248 0.0648321 0.0328772 0.151694 0.0706013 0.0328772 0.151748 0.0778942 0.0301473 0.145714 0.0822375 0.0328772 0.145031 0.0897837 0.0301473 0.138493 0.0938897 0.0328772 0.132478 0.107445 0.0301473 0.125166 0.111036 0.0328772 0.122366 0.118834 0.0301473 0.116775 0.124333 0.0301473 0.108712 0.127191 0.0328772 0.0978714 0.1397 0.0301473 0.0908822 0.144345 0.0301473 0.0835678 0.148699 0.0301473 0.0680317 0.156418 0.0301473 0.0692407 0.159198 0.0270916 0.066734 0.153435 0.0328772 0.0514344 0.162633 0.0301473 0.0428057 0.165114 0.0301473 0.0339989 0.16715 0.0301473 0.0250487 0.168723 0.0301473 0.0159917 0.169821 0.0301473 0.00686591 0.170434 0.0301473 -0.00228946 0.170557 0.0301473 -0.0205312 0.169332 0.0301473 -0.0208961 0.172342 0.0270916 -0.0201396 0.166103 0.0328772 -0.0384224 0.166189 0.0301473 -0.0471444 0.163928 0.0301473 -0.0556719 0.161232 0.0301473 -0.063974 0.158121 0.0301473 -0.070649 0.151672 0.0328772 -0.0872647 0.14656 0.0301473 -0.107718 0.132257 0.0301473 -0.10124 0.137279 0.0301473 -0.103039 0.139719 0.0270916 -0.0993087 0.13466 0.0328772 -0.136484 0.0967869 0.0328772 -0.113845 0.127021 0.0301473 -0.14042 0.0909836 0.0328772 -0.15031 0.073501 0.0328772 -0.153006 0.067711 0.0328772 -0.155421 0.0619662 0.0328772 -0.162545 0.0396829 0.0328772 -0.161118 0.0451288 0.0328772 -0.164251 0.0460063 0.0301473 -0.162565 0.0516492 0.0301473 -0.160634 0.0573743 0.0301473 -0.164771 0.0290882 0.0328772 -0.163758 0.034334 0.0328772 -0.165596 0.0239507 0.0328772 -0.167975 0.0296538 0.0301473 -0.169478 0.0192936 0.0301473 -0.169973 0.0142886 0.0301473 -0.167065 0.00922437 0.0328772 -0.167257 0.00455206 0.0328772 -0.170313 -0.00940375 0.0301473 -0.169973 -0.0142886 0.0301473 -0.175238 -0.0199494 0.0237508 -0.1782 -0.0149802 0.0201657 -0.177681 -0.0202275 0.0201657 -0.16717 -0.0468239 0.0270916 -0.168651 -0.0411735 0.0270916 -0.171338 -0.0418296 0.0237508 -0.16809 -0.0534047 0.0237508 -0.165454 -0.0525671 0.0270916 -0.169834 -0.04757 0.0237508 -0.155981 -0.0690277 0.0301473 -0.158753 -0.0702544 0.0270916 -0.163829 -0.0653183 0.0237508 -0.161283 -0.0713739 0.0237508 -0.145694 -0.0944012 0.0270916 -0.139138 -0.0986689 0.0301473 -0.130084 -0.110333 0.0301473 -0.12725 -0.118092 0.0270916 -0.121741 -0.123764 0.0270916 -0.113845 -0.127021 0.0301473 -0.103039 -0.139719 0.0270916 -0.0960963 -0.144582 0.0270916 -0.0825056 -0.155882 0.0237508 -0.0812116 -0.153437 0.0270916 -0.0797935 -0.150758 0.0301473 -0.0651109 -0.160931 0.0270916 -0.0566612 -0.164097 0.0270916 -0.0479822 -0.166841 0.0270916 -0.0391053 -0.169142 0.0270916 -0.0300645 -0.170981 0.0270916 -0.0208961 -0.172342 0.0270916 -0.0116382 -0.173213 0.0270916 0.00709928 -0.176227 0.0237508 0.00698793 -0.173463 0.0270916 0.00686591 -0.170434 0.0301473 0.0346031 -0.17012 0.0270916 0.0435664 -0.168049 0.0270916 0.0523485 -0.165523 0.0270916 0.070344 -0.161735 0.0237508 0.0692407 -0.159198 0.0270916 0.0680317 -0.156418 0.0301473 0.0850529 -0.151342 0.0270916 0.10638 -0.137192 0.0270916 0.0996107 -0.142183 0.0270916 0.101198 -0.144449 0.0237508 0.0978714 -0.1397 0.0301473 0.124541 -0.120946 0.0270916 0.11885 -0.126543 0.0270916 0.120744 -0.128559 0.0237508 0.116775 -0.124333 0.0301473 0.1276 -0.113195 0.0301473 0.134833 -0.109355 0.0270916 0.137005 -0.10161 0.0301473 0.151188 -0.0853266 0.0270916 0.147608 -0.0913793 0.0270916 0.14996 -0.0928354 0.0237508 0.145031 -0.0897837 0.0301473 0.148548 -0.0838367 0.0301473 0.154445 -0.0792785 0.0270916 0.154644 -0.0719741 0.0301473 0.157247 -0.0660928 0.0301473 0.159572 -0.0602645 0.0301473 0.165007 -0.0432185 0.0301473 0.166351 -0.0377153 0.0301473 0.167484 -0.0323142 0.0301473 0.168419 -0.027021 0.0301473 0.169169 -0.0218405 0.0301473 0.169746 -0.0167762 0.0301473 0.170162 -0.0118311 0.0301473 0.170429 -0.00700687 0.0301473 0.170557 -0.00230493 0.0301473 0.170557 0.00230493 0.0301473 0.170429 0.00700687 0.0301473 0.170162 0.0118311 0.0301473 0.169746 0.0167762 0.0301473 0.17046 0.0328885 0.0270916 0.171412 0.0275013 0.0270916 0.174143 0.0279395 0.0237508 0.168419 0.027021 0.0301473 0.167484 0.0323142 0.0301473 0.166351 0.0377153 0.0301473 0.165007 0.0432185 0.0301473 0.159572 0.0602645 0.0301473 0.154445 0.0792785 0.0270916 0.148548 0.0838367 0.0301473 0.147608 0.0913793 0.0270916 0.141186 0.0957154 0.0301473 0.13944 0.103416 0.0270916 0.124541 0.120946 0.0270916 0.129868 0.115207 0.0270916 0.131937 0.117043 0.0237508 0.1276 0.113195 0.0301473 0.10638 0.137192 0.0270916 0.112795 0.131968 0.0270916 0.114592 0.134071 0.0237508 0.110826 0.129664 0.0301473 0.0996107 0.142183 0.0270916 0.0924973 0.14691 0.0270916 0.077294 0.155448 0.0270916 0.0785256 0.157925 0.0237508 0.0759443 0.152733 0.0301473 0.0609166 0.162565 0.0270916 0.0523485 0.165523 0.0270916 0.0435664 0.168049 0.0270916 0.0346031 0.17012 0.0270916 0.0254939 0.171722 0.0270916 0.0162759 0.172839 0.0270916 -0.00236728 0.176354 0.0237508 -0.0116382 0.173213 0.0270916 -0.00233015 0.173588 0.0270916 -0.0118236 0.175973 0.0237508 -0.0114349 0.170189 0.0301473 -0.0300645 0.170981 0.0270916 -0.0391053 0.169142 0.0270916 -0.0479822 0.166841 0.0270916 -0.0566612 0.164097 0.0270916 -0.0812116 0.153437 0.0270916 -0.0733028 0.157369 0.0270916 -0.0744708 0.159877 0.0237508 -0.0720228 0.154621 0.0301473 -0.0888156 0.149165 0.0270916 -0.0944183 0.142057 0.0301473 -0.109632 0.134607 0.0270916 -0.121741 0.123764 0.0270916 -0.134505 0.114083 0.0237508 -0.139138 0.0986689 0.0301473 -0.115868 0.129279 0.0270916 -0.14315 0.0927528 0.0301473 -0.165454 0.0525671 0.0270916 -0.163488 0.058394 0.0270916 -0.166094 0.0593244 0.0237508 -0.153233 0.0749303 0.0301473 -0.155981 0.0690277 0.0301473 -0.158444 0.0631711 0.0301473 -0.165706 0.0404546 0.0301473 -0.17096 0.0301808 0.0270916 -0.171816 0.0248504 0.0270916 -0.168816 0.0244164 0.0301473 -0.166943 0.0350016 0.0301473 -0.17249 0.0196365 0.0270916 -0.172994 0.0145426 0.0270916 -0.170509 0.00464057 0.0301473 -0.170313 0.00940375 0.0301473 -0.182582 -0.00496914 0.0124252 -0.182802 0 0.0120091 -0.183732 0 0.00908708 -0.17334 -0.00957087 0.0270916 -0.181653 0 0.0148524 -0.180869 -0.00492252 0.0163769 -0.171816 -0.0248504 0.0270916 -0.176987 -0.0255982 0.0201657 -0.174554 -0.0252463 0.0237508 -0.176105 -0.0310891 0.0201657 -0.172617 -0.0361913 0.0237508 -0.173685 -0.0306617 0.0237508 -0.168409 -0.0601513 0.0201657 -0.166094 -0.0593244 0.0237508 -0.170433 -0.0541491 0.0201657 -0.155957 -0.0762619 0.0270916 -0.158442 -0.0774771 0.0237508 -0.13638 -0.115673 0.0201657 -0.129278 -0.119974 0.0237508 -0.134505 -0.114083 0.0237508 -0.132395 -0.112293 0.0270916 -0.119355 -0.133169 0.0201657 -0.111379 -0.136752 0.0237508 -0.117714 -0.131339 0.0237508 -0.115868 -0.129279 0.0270916 -0.104681 -0.141945 0.0237508 -0.0976275 -0.146885 0.0237508 -0.0888156 -0.149165 0.0270916 -0.0744708 -0.159877 0.0237508 -0.0661484 -0.163496 0.0237508 -0.0575641 -0.166712 0.0237508 -0.0487468 -0.1695 0.0237508 -0.0397284 -0.171837 0.0237508 -0.0305435 -0.173705 0.0237508 -0.0119884 -0.178426 0.0201657 -0.00236728 -0.176354 0.0237508 -0.0118236 -0.175973 0.0237508 -0.00240027 -0.178812 0.0201657 -0.00233015 -0.173588 0.0270916 0.0165352 -0.175593 0.0237508 0.0259001 -0.174458 0.0237508 0.0351545 -0.172831 0.0237508 0.0442606 -0.170726 0.0237508 0.0531826 -0.168161 0.0237508 0.0609166 -0.162565 0.0270916 0.0785256 -0.157925 0.0237508 0.0864082 -0.153753 0.0237508 0.0924973 -0.14691 0.0270916 0.108075 -0.139378 0.0237508 0.112795 -0.131968 0.0270916 0.136981 -0.111097 0.0237508 0.131937 -0.117043 0.0237508 0.133776 -0.118674 0.0201657 0.129868 -0.115207 0.0270916 0.145985 -0.0989687 0.0237508 0.141662 -0.105064 0.0237508 0.143636 -0.106528 0.0201657 0.13944 -0.103416 0.0270916 0.143695 -0.0974165 0.0270916 0.162592 -0.0683392 0.0237508 0.1599 -0.0744205 0.0237508 0.162129 -0.0754578 0.0201657 0.157392 -0.0732532 0.0270916 0.160042 -0.0672673 0.0270916 0.162408 -0.0613355 0.0270916 0.170615 -0.0446875 0.0237508 0.168993 -0.0504761 0.0237508 0.171348 -0.0511797 0.0201657 0.166342 -0.0496845 0.0270916 0.167939 -0.0439866 0.0270916 0.169307 -0.0383856 0.0270916 0.17046 -0.0328885 0.0270916 0.171412 -0.0275013 0.0270916 0.172175 -0.0222286 0.0270916 0.172762 -0.0170744 0.0270916 0.173186 -0.0120413 0.0270916 0.173457 -0.0071314 0.0270916 0.173588 -0.00234589 0.0270916 0.173588 0.00234589 0.0270916 0.173457 0.0071314 0.0270916 0.173186 0.0120413 0.0270916 0.172762 0.0170744 0.0270916 0.172175 0.0222286 0.0270916 0.169307 0.0383856 0.0270916 0.167939 0.0439866 0.0270916 0.168993 0.0504761 0.0237508 0.164503 0.0554707 0.0270916 0.162408 0.0613355 0.0270916 0.162592 0.0683392 0.0237508 0.157392 0.0732532 0.0270916 0.14996 0.0928354 0.0237508 0.153597 0.0866862 0.0237508 0.155738 0.0878945 0.0201657 0.151188 0.0853266 0.0270916 0.143695 0.0974165 0.0270916 0.141662 0.105064 0.0237508 0.134833 0.109355 0.0270916 0.126526 0.122873 0.0237508 0.11885 0.126543 0.0270916 0.108075 0.139378 0.0237508 0.101198 0.144449 0.0237508 0.0876125 0.155896 0.0201657 0.0864082 0.153753 0.0237508 0.0850529 0.151342 0.0270916 0.070344 0.161735 0.0237508 0.0618873 0.165156 0.0237508 0.0531826 0.168161 0.0237508 0.0442606 0.170726 0.0237508 0.0351545 0.172831 0.0237508 0.0259001 0.174458 0.0237508 0.00719823 0.178684 0.0201657 0.00709928 0.176227 0.0237508 0.00698793 0.173463 0.0270916 -0.021229 0.175088 0.0237508 -0.0305435 0.173705 0.0237508 -0.0397284 0.171837 0.0237508 -0.0487468 0.1695 0.0237508 -0.0670704 0.165775 0.0201657 -0.0661484 0.163496 0.0237508 -0.0651109 0.160931 0.0270916 -0.0825056 0.155882 0.0237508 -0.0902308 0.151542 0.0237508 -0.0960963 0.144582 0.0270916 -0.104681 0.141945 0.0237508 -0.111379 0.136752 0.0237508 -0.123681 0.125736 0.0237508 -0.12725 0.118092 0.0270916 -0.117714 0.131339 0.0237508 -0.145694 0.0944012 0.0270916 -0.152856 0.0823008 0.0270916 -0.155957 0.0762619 0.0270916 -0.158753 0.0702544 0.0270916 -0.16126 0.0642938 0.0270916 -0.16717 0.0468239 0.0270916 -0.168651 0.0411735 0.0270916 -0.16809 0.0534047 0.0237508 -0.16991 0.0356236 0.0270916 -0.173685 0.0306617 0.0237508 -0.175238 0.0199494 0.0237508 -0.17575 0.0147743 0.0237508 -0.17354 0.00472304 0.0270916 -0.17334 0.00957087 0.0270916 -0.176102 -0.00972337 0.0237508 -0.17575 -0.0147743 0.0237508 -0.173726 -0.0424126 0.0201657 -0.175023 -0.0366957 0.0201657 -0.177086 -0.0371282 0.0163769 -0.172201 -0.0482331 0.0201657 -0.175774 -0.0429124 0.0163769 -0.166113 -0.0662287 0.0201657 -0.163531 -0.0723687 0.0201657 -0.16807 -0.0670092 0.0163769 -0.165458 -0.0732215 0.0163769 -0.145873 -0.103445 0.0201657 -0.139366 -0.10809 0.0237508 -0.13108 -0.121646 0.0201657 -0.123681 -0.125736 0.0237508 -0.112932 -0.138658 0.0201657 -0.10614 -0.143923 0.0201657 -0.0925666 -0.155465 0.0163769 -0.0836556 -0.158055 0.0201657 -0.0914884 -0.153654 0.0201657 -0.0902308 -0.151542 0.0237508 -0.0755088 -0.162105 0.0201657 -0.0670704 -0.165775 0.0201657 -0.0583664 -0.169035 0.0201657 -0.0494262 -0.171862 0.0201657 -0.0313342 -0.178202 0.0163769 -0.0215249 -0.177528 0.0201657 -0.0309692 -0.176126 0.0201657 -0.0217786 -0.17962 0.0163769 -0.021229 -0.175088 0.0237508 0.00719823 -0.178684 0.0201657 0.0167657 -0.178041 0.0201657 0.0262611 -0.17689 0.0201657 0.0356445 -0.17524 0.0201657 0.0448775 -0.173106 0.0201657 0.0634893 -0.169431 0.0163769 0.0713245 -0.163989 0.0201657 0.0627498 -0.167458 0.0201657 0.0618873 -0.165156 0.0237508 0.0796201 -0.160126 0.0201657 0.0876125 -0.155896 0.0201657 0.0939712 -0.149251 0.0237508 0.102608 -0.146462 0.0201657 0.109581 -0.141321 0.0201657 0.114592 -0.134071 0.0237508 0.122427 -0.130351 0.0201657 0.126526 -0.122873 0.0237508 0.15205 -0.0941293 0.0201657 0.153597 -0.0866862 0.0237508 0.156906 -0.0805417 0.0237508 0.164996 -0.0623128 0.0237508 0.167125 -0.0563546 0.0237508 0.172005 -0.0389972 0.0237508 0.173176 -0.0334125 0.0237508 0.174143 -0.0279395 0.0237508 0.174918 -0.0225828 0.0237508 0.175515 -0.0173465 0.0237508 0.175945 -0.0122332 0.0237508 0.176221 -0.00724503 0.0237508 0.176354 -0.00238327 0.0237508 0.176354 0.00238327 0.0237508 0.176221 0.00724503 0.0237508 0.175945 0.0122332 0.0237508 0.175515 0.0173465 0.0237508 0.174918 0.0225828 0.0237508 0.174402 0.0395408 0.0201657 0.17559 0.0338783 0.0201657 0.177659 0.0342775 0.0163769 0.173176 0.0334125 0.0237508 0.172005 0.0389972 0.0237508 0.170615 0.0446875 0.0237508 0.167295 0.0631813 0.0201657 0.169454 0.0571401 0.0201657 0.171451 0.0578135 0.0163769 0.167125 0.0563546 0.0237508 0.164996 0.0623128 0.0237508 0.164039 0.076347 0.0163769 0.159093 0.0816643 0.0201657 0.162129 0.0754578 0.0201657 0.1599 0.0744205 0.0237508 0.156906 0.0805417 0.0237508 0.149764 0.101531 0.0163769 0.143636 0.106528 0.0201657 0.14802 0.100348 0.0201657 0.145985 0.0989687 0.0237508 0.136981 0.111097 0.0237508 0.133776 0.118674 0.0201657 0.123869 0.131887 0.0163769 0.11619 0.13594 0.0201657 0.122427 0.130351 0.0201657 0.120744 0.128559 0.0237508 0.109581 0.141321 0.0201657 0.102608 0.146462 0.0201657 0.0939712 0.149251 0.0237508 0.0796201 0.160126 0.0201657 0.0713245 0.163989 0.0201657 0.0627498 0.167458 0.0201657 0.0539239 0.170505 0.0201657 0.0448775 0.173106 0.0201657 0.0265706 0.178974 0.0163769 0.0167657 0.178041 0.0201657 0.0262611 0.17689 0.0201657 0.0169633 0.180139 0.0163769 0.0165352 0.175593 0.0237508 -0.00240027 0.178812 0.0201657 -0.0119884 0.178426 0.0201657 -0.0215249 0.177528 0.0201657 -0.0309692 0.176126 0.0201657 -0.0402821 0.174233 0.0201657 -0.0590543 0.171027 0.0163769 -0.0583664 0.169035 0.0201657 -0.0575641 0.166712 0.0237508 -0.0755088 0.162105 0.0201657 -0.0836556 0.158055 0.0201657 -0.100155 0.150688 0.0163769 -0.10614 0.143923 0.0201657 -0.0989883 0.148933 0.0201657 -0.0976275 0.146885 0.0237508 -0.120761 0.134739 0.0163769 -0.125405 0.127488 0.0201657 -0.119355 0.133169 0.0201657 -0.129278 0.119974 0.0237508 -0.13638 0.115673 0.0201657 -0.15575 0.0920851 0.0163769 -0.155291 0.0836122 0.0237508 -0.158442 0.0774771 0.0237508 -0.161283 0.0713739 0.0237508 -0.163829 0.0653183 0.0237508 -0.153936 0.0910126 0.0201657 -0.172617 0.0361913 0.0237508 -0.171338 0.0418296 0.0237508 -0.173726 0.0424126 0.0201657 -0.169834 0.04757 0.0237508 -0.170433 0.0541491 0.0201657 -0.168409 0.0601513 0.0201657 -0.174554 0.0252463 0.0237508 -0.176105 0.0310891 0.0201657 -0.177681 0.0202275 0.0201657 -0.1782 0.0149802 0.0201657 -0.176305 0.0047983 0.0237508 -0.176102 0.00972337 0.0237508 -0.180304 0 0.0176059 -0.178557 -0.0098589 0.0201657 -0.184656 -0.00502559 0.00419604 -0.183859 -0.00500389 0.00835136 -0.184423 0 0.0060991 -0.181477 -0.0206597 0.0124252 -0.18328 -0.0154073 0.00835136 -0.182746 -0.0208042 0.00835136 -0.182033 -0.026328 0.00835136 -0.180769 -0.0261452 0.0124252 -0.174075 -0.0553062 0.0124252 -0.172442 -0.0547872 0.0163769 -0.175881 -0.0492637 0.0124252 -0.170393 -0.0608602 0.0163769 -0.172007 -0.0614366 0.0124252 -0.15575 -0.0920851 0.0163769 -0.150079 -0.0972421 0.0201657 -0.147592 -0.104664 0.0163769 -0.141309 -0.109597 0.0201657 -0.137987 -0.117036 0.0163769 -0.132624 -0.12308 0.0163769 -0.125405 -0.127488 0.0201657 -0.120761 -0.134739 0.0163769 -0.114262 -0.140292 0.0163769 -0.101103 -0.152115 0.0124252 -0.100155 -0.150688 0.0163769 -0.0989883 -0.148933 0.0201657 -0.0846415 -0.159918 0.0163769 -0.0763986 -0.164015 0.0163769 -0.0678608 -0.167728 0.0163769 -0.0590543 -0.171027 0.0163769 -0.0411429 -0.177956 0.0124252 -0.0407568 -0.176286 0.0163769 -0.0402821 -0.174233 0.0201657 -0.0121297 -0.180529 0.0163769 -0.00242856 -0.18092 0.0163769 0.00728306 -0.180789 0.0163769 0.0169633 -0.180139 0.0163769 0.0265706 -0.178974 0.0163769 0.0360646 -0.177305 0.0163769 0.0550761 -0.174148 0.0124252 0.0545594 -0.172514 0.0163769 0.0539239 -0.170505 0.0201657 0.072165 -0.165922 0.0163769 0.0805584 -0.162013 0.0163769 0.097317 -0.154565 0.0124252 0.103818 -0.148188 0.0163769 0.0964039 -0.153115 0.0163769 0.095281 -0.151331 0.0201657 0.118672 -0.138844 0.0124252 0.123869 -0.131887 0.0163769 0.117559 -0.137542 0.0163769 0.11619 -0.13594 0.0201657 0.128289 -0.124585 0.0201657 0.135353 -0.120073 0.0163769 0.13889 -0.112646 0.0201657 0.145329 -0.107784 0.0163769 0.14802 -0.100348 0.0201657 0.153842 -0.0952386 0.0163769 0.155738 -0.0878945 0.0201657 0.159093 -0.0816643 0.0201657 0.164039 -0.076347 0.0163769 0.164858 -0.0692917 0.0201657 0.167295 -0.0631813 0.0201657 0.169454 -0.0571401 0.0201657 0.176458 -0.0400067 0.0163769 0.175032 -0.0458443 0.0163769 0.17669 -0.0462785 0.0124252 0.172993 -0.0453104 0.0201657 0.174402 -0.0395408 0.0201657 0.17559 -0.0338783 0.0201657 0.17657 -0.0283289 0.0201657 0.177357 -0.0228976 0.0201657 0.177961 -0.0175882 0.0201657 0.178398 -0.0124037 0.0201657 0.178678 -0.00734601 0.0201657 0.178812 -0.00241649 0.0201657 0.178812 0.00241649 0.0201657 0.178678 0.00734601 0.0201657 0.178398 0.0124037 0.0201657 0.177961 0.0175882 0.0201657 0.177357 0.0228976 0.0201657 0.17657 0.0283289 0.0201657 0.172993 0.0453104 0.0201657 0.171348 0.0511797 0.0201657 0.164858 0.0692917 0.0201657 0.157573 0.0889303 0.0163769 0.15205 0.0941293 0.0201657 0.141858 0.115053 0.0124252 0.135353 0.120073 0.0163769 0.140527 0.113973 0.0163769 0.13889 0.112646 0.0201657 0.128289 0.124585 0.0201657 0.117559 0.137542 0.0163769 0.110873 0.142986 0.0163769 0.097317 0.154565 0.0124252 0.088645 0.157734 0.0163769 0.0964039 0.153115 0.0163769 0.095281 0.151331 0.0201657 0.0805584 0.162013 0.0163769 0.072165 0.165922 0.0163769 0.0634893 0.169431 0.0163769 0.0545594 0.172514 0.0163769 0.0364061 0.178985 0.0124252 0.0360646 0.177305 0.0163769 0.0356445 0.17524 0.0201657 0.00728306 0.180789 0.0163769 -0.00242856 0.18092 0.0163769 -0.0121297 0.180529 0.0163769 -0.0217786 0.17962 0.0163769 -0.0313342 0.178202 0.0163769 -0.0504824 0.175535 0.0124252 -0.0500087 0.173888 0.0163769 -0.0494262 0.171862 0.0201657 -0.0678608 0.167728 0.0163769 -0.0763986 0.164015 0.0163769 -0.0846415 0.159918 0.0163769 -0.0914884 0.153654 0.0201657 -0.107391 0.14562 0.0163769 -0.112932 0.138658 0.0201657 -0.13388 0.124245 0.0124252 -0.137987 0.117036 0.0163769 -0.132624 0.12308 0.0163769 -0.13108 0.121646 0.0201657 -0.126883 0.128991 0.0163769 -0.157456 0.0847776 0.0201657 -0.16065 0.078557 0.0201657 -0.163531 0.0723687 0.0201657 -0.166113 0.0662287 0.0201657 -0.172201 0.0482331 0.0201657 -0.170393 0.0608602 0.0163769 -0.172442 0.0547872 0.0163769 -0.175023 0.0366957 0.0201657 -0.176987 0.0255982 0.0201657 -0.178181 0.0314555 0.0163769 -0.179775 0.0204659 0.0163769 -0.1803 0.0151568 0.0163769 -0.178762 0.00486518 0.0201657 -0.178557 0.0098589 0.0201657 -0.185 0 6.08402e-17 -0.184932 -0.00503308 3.33068e-17 -0.184852 0 0.00306329 -0.180661 -0.00997508 0.0163769 -0.1803 -0.0151568 0.0163769 -0.179775 -0.0204659 0.0163769 -0.179073 -0.0258999 0.0163769 -0.178181 -0.0314555 0.0163769 -0.181126 -0.0319754 0.00835136 -0.178763 -0.0374798 0.0124252 -0.179868 -0.0317534 0.0124252 -0.177438 -0.0433189 0.0124252 -0.180013 -0.0377419 0.00835136 -0.17423 -0.0488015 0.0163769 -0.169662 -0.0676438 0.0124252 -0.17321 -0.0618662 0.00835136 -0.170848 -0.0681168 0.00835136 -0.165947 -0.0811471 0.00419604 -0.154357 -0.100014 0.00835136 -0.14899 -0.105655 0.0124252 -0.153286 -0.09932 0.0124252 -0.151847 -0.0983881 0.0163769 -0.142974 -0.110888 0.0163769 -0.139294 -0.118144 0.0124252 -0.12898 -0.131123 0.00835136 -0.121905 -0.136015 0.0124252 -0.128084 -0.130212 0.0124252 -0.126883 -0.128991 0.0163769 -0.115345 -0.141621 0.0124252 -0.107391 -0.14562 0.0163769 -0.0934433 -0.156937 0.0124252 -0.0854432 -0.161432 0.0124252 -0.0771222 -0.165569 0.0124252 -0.0685035 -0.169317 0.0124252 -0.0508354 -0.176762 0.00835136 -0.0504824 -0.175535 0.0124252 -0.0500087 -0.173888 0.0163769 -0.031631 -0.17989 0.0124252 -0.0219848 -0.181322 0.0124252 -0.0122446 -0.182239 0.0124252 -0.00245156 -0.182633 0.0124252 0.00735204 -0.182502 0.0124252 0.0171239 -0.181845 0.0124252 0.0268222 -0.18067 0.0124252 0.046157 -0.178041 0.00835136 0.0458365 -0.176805 0.0124252 0.0454064 -0.175146 0.0163769 0.0640907 -0.171036 0.0124252 0.0728485 -0.167493 0.0124252 0.0813214 -0.163547 0.0124252 0.088645 -0.157734 0.0163769 0.104801 -0.149592 0.0124252 0.110873 -0.142986 0.0163769 0.125043 -0.133136 0.0124252 0.129801 -0.126054 0.0163769 0.140527 -0.113973 0.0163769 0.136635 -0.12121 0.0124252 0.146705 -0.108805 0.0124252 0.149764 -0.101531 0.0163769 0.160178 -0.0904003 0.00835136 0.162492 -0.0834093 0.0124252 0.159065 -0.0897726 0.0124252 0.157573 -0.0889303 0.0163769 0.160968 -0.0826267 0.0163769 0.169558 -0.0712672 0.00835136 0.17087 -0.0645314 0.0124252 0.168381 -0.0707723 0.0124252 0.166801 -0.0701083 0.0163769 0.169267 -0.0639259 0.0163769 0.171451 -0.0578135 0.0163769 0.173368 -0.0517828 0.0163769 0.177659 -0.0342775 0.0163769 0.178651 -0.0286627 0.0163769 0.179447 -0.0231674 0.0163769 0.180059 -0.0177955 0.0163769 0.1805 -0.0125499 0.0163769 0.180783 -0.00743258 0.0163769 0.180919 -0.00244497 0.0163769 0.180919 0.00244497 0.0163769 0.180783 0.00743258 0.0163769 0.1805 0.0125499 0.0163769 0.180059 0.0177955 0.0163769 0.179447 0.0231674 0.0163769 0.178651 0.0286627 0.0163769 0.179374 0.0406681 0.00835136 0.17669 0.0462785 0.0124252 0.178129 0.0403857 0.0124252 0.176458 0.0400067 0.0163769 0.175032 0.0458443 0.0163769 0.173368 0.0517828 0.0163769 0.173075 0.058361 0.0124252 0.169267 0.0639259 0.0163769 0.166801 0.0701083 0.0163769 0.160968 0.0826267 0.0163769 0.165593 0.0770701 0.0124252 0.159065 0.0897726 0.0124252 0.153842 0.0952386 0.0163769 0.145329 0.107784 0.0163769 0.151183 0.102492 0.0124252 0.136635 0.12121 0.0124252 0.129801 0.126054 0.0163769 0.125043 0.133136 0.0124252 0.118672 0.138844 0.0124252 0.105534 0.150638 0.00835136 0.104801 0.149592 0.0124252 0.103818 0.148188 0.0163769 0.0894846 0.159228 0.0124252 0.0813214 0.163547 0.0124252 0.0728485 0.167493 0.0124252 0.0554613 0.175366 0.00835136 0.0458365 0.176805 0.0124252 0.0550761 0.174148 0.0124252 0.046157 0.178041 0.00835136 0.0454064 0.175146 0.0163769 0.0268222 0.18067 0.0124252 0.0171239 0.181845 0.0124252 0.00735204 0.182502 0.0124252 -0.00245156 0.182633 0.0124252 -0.0122446 0.182239 0.0124252 -0.0219848 0.181322 0.0124252 -0.0414306 0.1792 0.00835136 -0.0411429 0.177956 0.0124252 -0.0407568 0.176286 0.0163769 -0.0596136 0.172647 0.0124252 -0.0685035 0.169317 0.0124252 -0.0771222 0.165569 0.0124252 -0.0940967 0.158034 0.00835136 -0.101103 0.152115 0.0124252 -0.0934433 0.156937 0.0124252 -0.0925666 0.155465 0.0163769 -0.108408 0.146999 0.0124252 -0.114262 0.140292 0.0163769 -0.121905 0.136015 0.0124252 -0.145338 0.112721 0.00835136 -0.144328 0.111938 0.0124252 -0.158325 0.0936073 0.00835136 -0.128084 0.130212 0.0124252 -0.162543 0.0794828 0.0163769 -0.165458 0.0732215 0.0163769 -0.16807 0.0670092 0.0163769 -0.175774 0.0429124 0.0163769 -0.17423 0.0488015 0.0163769 -0.175881 0.0492637 0.0124252 -0.174075 0.0553062 0.0124252 -0.172007 0.0614366 0.0124252 -0.177086 0.0371282 0.0163769 -0.179073 0.0258999 0.0163769 -0.179868 0.0317534 0.0124252 -0.181477 0.0206597 0.0124252 -0.182008 0.0153003 0.0124252 -0.180661 0.00997508 0.0163769 -0.180869 0.00492252 0.0163769 -0.182372 -0.0100696 0.0124252 -0.182008 -0.0153003 0.0124252 -0.17711 -0.0496082 0.00835136 -0.178679 -0.0436218 0.00835136 -0.179454 -0.043811 0.00419604 -0.176053 -0.0559344 0.00419604 -0.175292 -0.0556929 0.00835136 -0.177879 -0.0498233 0.00419604 -0.167025 -0.073915 0.0124252 -0.145338 -0.112721 0.00835136 -0.150682 -0.106855 0.00419604 -0.145968 -0.11321 0.00419604 -0.144328 -0.111938 0.0124252 -0.13388 -0.124245 0.0124252 -0.140268 -0.118971 0.00835136 -0.122758 -0.136966 0.00835136 -0.109166 -0.148027 0.00835136 -0.116655 -0.14323 0.00419604 -0.109639 -0.148669 0.00419604 -0.108408 -0.146999 0.0124252 -0.10181 -0.153179 0.00835136 -0.0940967 -0.158034 0.00835136 -0.0860406 -0.162561 0.00835136 -0.0776615 -0.166727 0.00835136 -0.0600304 -0.173855 0.00835136 -0.0692817 -0.17124 0.00419604 -0.0602908 -0.174609 0.00419604 -0.0596136 -0.172647 0.0124252 -0.0414306 -0.1792 0.00835136 -0.0318521 -0.181148 0.00835136 -0.0221386 -0.18259 0.00835136 -0.0123302 -0.183513 0.00835136 -0.00246871 -0.18391 0.00835136 0.00740345 -0.183778 0.00835136 0.0172437 -0.183117 0.00835136 0.0366607 -0.180236 0.00835136 0.0271269 -0.182722 0.00419604 0.0368197 -0.181018 0.00419604 0.0364061 -0.178985 0.0124252 0.0554613 -0.175366 0.00835136 0.0645388 -0.172232 0.00835136 0.0733579 -0.168664 0.00835136 0.0901103 -0.160341 0.00835136 0.0822452 -0.165405 0.00419604 0.0905012 -0.161036 0.00419604 0.0894846 -0.159228 0.0124252 0.0979974 -0.155646 0.00835136 0.111923 -0.144341 0.0124252 0.105534 -0.150638 0.00835136 0.119502 -0.139815 0.00835136 0.131947 -0.128137 0.00835136 0.126463 -0.134649 0.00419604 0.132519 -0.128693 0.00419604 0.13103 -0.127248 0.0124252 0.141858 -0.115053 0.0124252 0.13759 -0.122057 0.00835136 0.147731 -0.109566 0.00835136 0.151183 -0.102492 0.0124252 0.155299 -0.0961407 0.0124252 0.165593 -0.0770701 0.0124252 0.173075 -0.058361 0.0124252 0.17501 -0.0522733 0.0124252 0.183477 -0.0236878 3.20609e-17 0.182392 -0.0292629 -0.00419604 0.183204 -0.0236526 -0.00419604 0.178129 -0.0403857 0.0124252 0.179342 -0.0346022 0.0124252 0.180343 -0.0289342 0.0124252 0.181146 -0.0233869 0.0124252 0.181764 -0.0179641 0.0124252 0.18221 -0.0126687 0.0124252 0.182496 -0.00750298 0.0124252 0.182633 -0.00246813 0.0124252 0.182633 0.00246813 0.0124252 0.182496 0.00750298 0.0124252 0.18221 0.0126687 0.0124252 0.181764 0.0179641 0.0124252 0.181146 0.0233869 0.0124252 0.180343 0.0289342 0.0124252 0.179342 0.0346022 0.0124252 0.17501 0.0522733 0.0124252 0.172065 0.0649826 0.00835136 0.175041 0.059024 0.00419604 0.172811 0.0652645 0.00419604 0.17087 0.0645314 0.0124252 0.168381 0.0707723 0.0124252 0.162492 0.0834093 0.0124252 0.166751 0.077609 0.00835136 0.155299 0.0961407 0.0124252 0.160178 0.0904003 0.00835136 0.146705 0.108805 0.0124252 0.15224 0.103209 0.00835136 0.14285 0.115857 0.00835136 0.131947 0.128137 0.00835136 0.138187 0.122587 0.00419604 0.132519 0.128693 0.00419604 0.13103 0.127248 0.0124252 0.125917 0.134067 0.00835136 0.111923 0.144341 0.0124252 0.119502 0.139815 0.00835136 0.0979974 0.155646 0.00835136 0.0901103 0.160341 0.00835136 0.0818901 0.164691 0.00835136 0.0645388 0.172232 0.00835136 0.0736761 0.169396 0.00419604 0.0648187 0.172979 0.00419604 0.0640907 0.171036 0.0124252 0.0366607 0.180236 0.00835136 0.0270098 0.181933 0.00835136 0.0172437 0.183117 0.00835136 0.00740345 0.183778 0.00835136 -0.00246871 0.18391 0.00835136 -0.0123302 0.183513 0.00835136 -0.0318521 0.181148 0.00835136 -0.0222346 0.183382 0.00419604 -0.0319903 0.181933 0.00419604 -0.031631 0.17989 0.0124252 -0.0508354 0.176762 0.00835136 -0.0600304 0.173855 0.00835136 -0.0689825 0.170501 0.00835136 -0.0860406 0.162561 0.00835136 -0.0779983 0.16745 0.00419604 -0.0864138 0.163266 0.00419604 -0.0854432 0.161432 0.0124252 -0.10181 0.153179 0.00835136 -0.116151 0.142611 0.00835136 -0.109639 0.148669 0.00419604 -0.116655 0.14323 0.00419604 -0.115345 0.141621 0.0124252 -0.122758 0.136966 0.00835136 -0.139294 0.118144 0.0124252 -0.153286 0.09932 0.0124252 -0.175292 0.0556929 0.00835136 -0.17321 0.0618662 0.00835136 -0.173961 0.0621345 0.00419604 -0.164083 0.0802356 0.0124252 -0.167025 0.073915 0.0124252 -0.169662 0.0676438 0.0124252 -0.180013 0.0377419 0.00835136 -0.181126 0.0319754 0.00835136 -0.177438 0.0433189 0.0124252 -0.178763 0.0374798 0.0124252 -0.180769 0.0261452 0.0124252 -0.182372 0.0100696 0.0124252 -0.182582 0.00496914 0.0124252 -0.182803 0 -0.0120088 -0.182582 -0.00496914 -0.0124252 -0.183733 0 -0.00908643 -0.183647 -0.01014 0.00835136 -0.183859 -0.00500389 -0.00835136 -0.184656 -0.00502559 -0.00419604 -0.184423 0 -0.00609882 -0.183813 -0.0209255 3.1623e-17 -0.183539 -0.0208944 0.00419604 -0.18435 -0.0154972 3.21246e-17 -0.183095 -0.0264816 3.27791e-17 -0.182822 -0.0264422 0.00419604 -0.182183 -0.032162 3.21777e-17 -0.180794 -0.0379056 0.00419604 -0.181912 -0.0321141 0.00419604 -0.17422 -0.0622272 3.4152e-17 -0.173961 -0.0621345 0.00419604 -0.176315 -0.0560178 3.29417e-17 -0.162647 -0.0875728 0.00419604 -0.158325 -0.0936073 0.00835136 -0.159012 -0.0940133 0.00419604 -0.155027 -0.100448 0.00419604 -0.150031 -0.106394 0.00835136 -0.135603 -0.125844 3.36712e-17 -0.135401 -0.125657 0.00419604 -0.141086 -0.119665 3.21333e-17 -0.134817 -0.125114 0.00835136 -0.12954 -0.131692 0.00419604 -0.12329 -0.13756 0.00419604 -0.116151 -0.142611 0.00835136 -0.102252 -0.153843 0.00419604 -0.0945048 -0.15872 0.00419604 -0.0781146 -0.167699 3.45009e-17 -0.0779983 -0.16745 0.00419604 -0.0865426 -0.16351 3.30453e-17 -0.069385 -0.171496 3.29468e-17 -0.0689825 -0.170501 0.00835136 -0.0510558 -0.177529 0.00419604 -0.0416103 -0.179977 0.00419604 -0.0319903 -0.181933 0.00419604 -0.0222346 -0.183382 0.00419604 -0.0123837 -0.184309 0.00419604 -0.00247941 -0.184708 0.00419604 0.0173443 -0.184185 3.41196e-17 0.0173184 -0.183911 0.00419604 0.00744665 -0.18485 3.32932e-17 0.0271674 -0.182994 3.26845e-17 0.0270098 -0.181933 0.00835136 0.0463572 -0.178813 0.00419604 0.0557018 -0.176126 0.00419604 0.0648187 -0.172979 0.00419604 0.0823679 -0.165652 3.28276e-17 0.0737859 -0.169649 3.23504e-17 0.0818901 -0.164691 0.00835136 0.0984225 -0.156321 0.00419604 0.113363 -0.146198 3.18014e-17 0.113194 -0.14598 0.00419604 0.10615 -0.151517 3.31199e-17 0.112705 -0.14535 0.00835136 0.12002 -0.140422 0.00419604 0.125917 -0.134067 0.00835136 0.143684 -0.116533 3.3296e-17 0.14347 -0.11636 0.00419604 0.138393 -0.12277 3.2507e-17 0.14285 -0.115857 0.00835136 0.153128 -0.103811 3.18912e-17 0.1529 -0.103657 0.00419604 0.148593 -0.110205 3.40144e-17 0.15224 -0.103209 0.00835136 0.156385 -0.0968129 0.00835136 0.157064 -0.0972328 0.00419604 0.160872 -0.0907924 0.00419604 0.163629 -0.0839926 0.00835136 0.166751 -0.077609 0.00835136 0.167474 -0.0779456 0.00419604 0.170294 -0.0715763 0.00419604 0.172065 -0.0649826 0.00835136 0.174285 -0.0587691 0.00835136 0.176233 -0.0526388 0.00835136 0.177925 -0.0466021 0.00835136 0.179374 -0.0406681 0.00835136 0.180596 -0.0348441 0.00835136 0.181604 -0.0291365 0.00835136 0.182413 -0.0235504 0.00835136 0.183035 -0.0180897 0.00835136 0.183484 -0.0127573 0.00835136 0.183772 -0.00755545 0.00835136 0.18391 -0.00248538 0.00835136 0.18391 0.00248538 0.00835136 0.183772 0.00755545 0.00835136 0.183484 0.0127573 0.00835136 0.183035 0.0180897 0.00835136 0.182413 0.0235504 0.00835136 0.181604 0.0291365 0.00835136 0.180596 0.0348441 0.00835136 0.178963 0.046874 3.43272e-17 0.178697 0.0468043 0.00419604 0.180421 0.0409053 3.40536e-17 0.177925 0.0466021 0.00835136 0.176233 0.0526388 0.00835136 0.174285 0.0587691 0.00835136 0.169558 0.0712672 0.00835136 0.164583 0.0844826 3.35775e-17 0.164338 0.0843569 0.00419604 0.167724 0.0780619 3.24124e-17 0.163629 0.0839926 0.00835136 0.157298 0.0973778 3.32567e-17 0.157064 0.0972328 0.00419604 0.161112 0.0909278 3.22486e-17 0.156385 0.0968129 0.00835136 0.148593 0.110205 3.33944e-17 0.148372 0.110041 0.00419604 0.153128 0.103811 3.33644e-17 0.147731 0.109566 0.00835136 0.14347 0.11636 0.00419604 0.13759 0.122057 0.00835136 0.126463 0.134649 0.00419604 0.113363 0.146198 3.32921e-17 0.113194 0.14598 0.00419604 0.120199 0.140631 3.35142e-17 0.112705 0.14535 0.00835136 0.105991 0.151291 0.00419604 0.0984225 0.156321 0.00419604 0.0905012 0.161036 0.00419604 0.0737859 0.169649 3.34146e-17 0.0823679 0.165652 3.38798e-17 0.0733579 0.168664 0.00835136 0.0557018 0.176126 0.00419604 0.0463572 0.178813 0.00419604 0.0368197 0.181018 0.00419604 0.0271269 0.182722 0.00419604 0.0173184 0.183911 0.00419604 0.00743556 0.184575 0.00419604 -0.00247941 0.184708 0.00419604 -0.0222677 0.183655 3.31856e-17 -0.0124021 0.184584 3.37128e-17 -0.0221386 0.18259 0.00835136 -0.0416103 0.179977 0.00419604 -0.0510558 0.177529 0.00419604 -0.0602908 0.174609 0.00419604 -0.0692817 0.17124 0.00419604 -0.0776615 0.166727 0.00835136 -0.0945048 0.15872 0.00419604 -0.102252 0.153843 0.00419604 -0.109166 0.148027 0.00835136 -0.12329 0.13756 0.00419604 -0.135401 0.125657 0.00419604 -0.140268 0.118971 0.00835136 -0.140876 0.119487 0.00419604 -0.145968 0.11321 0.00419604 -0.150031 0.106394 0.00835136 -0.161945 0.0871946 0.00835136 -0.16523 0.0807966 0.00835136 -0.168193 0.0744319 0.00835136 -0.170848 0.0681168 0.00835136 -0.17711 0.0496082 0.00835136 -0.178679 0.0436218 0.00835136 -0.176053 0.0559344 0.00419604 -0.182033 0.026328 0.00835136 -0.182746 0.0208042 0.00835136 -0.181912 0.0321141 0.00419604 -0.18328 0.0154073 0.00835136 -0.183539 0.0208944 0.00419604 -0.184075 0.0154741 0.00419604 -0.183859 0.00500389 0.00835136 -0.183647 0.01014 0.00835136 -0.184444 -0.010184 0.00419604 -0.184075 -0.0154741 0.00419604 -0.179722 -0.0438763 3.25871e-17 -0.181063 -0.0379621 3.35326e-17 -0.180794 -0.0379056 -0.00419604 -0.178144 -0.0498976 3.2603e-17 -0.179454 -0.043811 -0.00419604 -0.173961 -0.0621345 -0.00419604 -0.166194 -0.0812681 3.33168e-17 -0.16289 -0.0877033 3.27923e-17 -0.159249 -0.0941535 3.30863e-17 -0.155258 -0.100598 3.31003e-17 -0.150907 -0.107015 3.21135e-17 -0.146186 -0.113379 3.21866e-17 -0.140876 -0.119487 0.00419604 -0.129733 -0.131888 3.31848e-17 -0.116655 -0.14323 -0.00419604 -0.116829 -0.143443 3.34094e-17 -0.12329 -0.13756 -0.00419604 -0.109803 -0.14889 3.37631e-17 -0.102404 -0.154072 3.26592e-17 -0.0864138 -0.163266 -0.00419604 -0.0945048 -0.15872 -0.00419604 -0.0864138 -0.163266 0.00419604 -0.0603807 -0.174869 3.21788e-17 -0.051132 -0.177793 3.30934e-17 -0.0416723 -0.180245 3.28787e-17 -0.032038 -0.182205 3.30551e-17 -0.0222677 -0.183655 3.31856e-17 -0.00247941 -0.184708 -0.00419604 -0.00248311 -0.184983 3.37493e-17 -0.0123837 -0.184309 -0.00419604 0.00743556 -0.184575 -0.00419604 0.00743556 -0.184575 0.00419604 0.0368746 -0.181288 3.34122e-17 0.0464263 -0.17908 3.32108e-17 0.0557849 -0.176389 3.42666e-17 0.0736761 -0.169396 -0.00419604 0.0648187 -0.172979 -0.00419604 0.0736761 -0.169396 0.00419604 0.0906361 -0.161276 3.32492e-17 0.0985692 -0.156554 3.27958e-17 0.105991 -0.151291 0.00419604 0.120199 -0.140631 3.20485e-17 0.126652 -0.134849 3.30151e-17 0.132716 -0.128885 3.31529e-17 0.138187 -0.122587 0.00419604 0.148372 -0.110041 0.00419604 0.164338 -0.0843569 -0.00419604 0.164583 -0.0844826 3.23444e-17 0.160872 -0.0907924 -0.00419604 0.164338 -0.0843569 0.00419604 0.172811 -0.0652645 -0.00419604 0.173069 -0.0653618 3.36554e-17 0.170294 -0.0715763 -0.00419604 0.172811 -0.0652645 0.00419604 0.175041 -0.059024 0.00419604 0.176998 -0.0528671 0.00419604 0.178697 -0.0468043 0.00419604 0.180152 -0.0408444 0.00419604 0.181379 -0.0349952 0.00419604 0.182392 -0.0292629 0.00419604 0.183204 -0.0236526 0.00419604 0.183829 -0.0181681 0.00419604 0.18428 -0.0128126 0.00419604 0.184569 -0.00758822 0.00419604 0.184708 -0.00249616 0.00419604 0.184708 0.00249616 0.00419604 0.184569 0.00758822 0.00419604 0.18428 0.0128126 0.00419604 0.183829 0.0181681 0.00419604 0.183204 0.0236526 0.00419604 0.182392 0.0292629 0.00419604 0.181379 0.0349952 0.00419604 0.180152 0.0408444 0.00419604 0.176998 0.0528671 0.00419604 0.175302 0.059112 3.36713e-17 0.173069 0.0653618 3.23219e-17 0.170294 0.0715763 0.00419604 0.167474 0.0779456 0.00419604 0.160872 0.0907924 0.00419604 0.1529 0.103657 0.00419604 0.143684 0.116533 3.32055e-17 0.138393 0.12277 3.35228e-17 0.132716 0.128885 3.27762e-17 0.126652 0.134849 3.28231e-17 0.12002 0.140422 0.00419604 0.10615 0.151517 3.2615e-17 0.0985692 0.156554 3.33082e-17 0.0822452 0.165405 -0.00419604 0.0905012 0.161036 -0.00419604 0.0822452 0.165405 0.00419604 0.0649154 0.173237 3.24628e-17 0.0557849 0.176389 3.3399e-17 0.0464263 0.17908 3.34292e-17 0.0368746 0.181288 3.34122e-17 0.0271674 0.182994 3.40095e-17 0.0173443 0.184185 3.32333e-17 -0.00247941 0.184708 -0.00419604 -0.00248311 0.184983 3.37493e-17 0.00743556 0.184575 -0.00419604 -0.0123837 0.184309 -0.00419604 -0.0123837 0.184309 0.00419604 -0.032038 0.182205 3.30551e-17 -0.0416723 0.180245 3.33171e-17 -0.051132 0.177793 3.30934e-17 -0.0603807 0.174869 3.19628e-17 -0.0779983 0.16745 -0.00419604 -0.0781146 0.167699 3.30193e-17 -0.0692817 0.17124 -0.00419604 -0.0865426 0.16351 3.17905e-17 -0.0946458 0.158957 3.30265e-17 -0.109639 0.148669 -0.00419604 -0.109803 0.14889 3.20599e-17 -0.102252 0.153843 -0.00419604 -0.116829 0.143443 3.15369e-17 -0.12954 0.131692 -0.00419604 -0.129733 0.131888 3.34701e-17 -0.12329 0.13756 -0.00419604 -0.135603 0.125844 3.28317e-17 -0.141086 0.119665 3.21791e-17 -0.146186 0.113379 3.43802e-17 -0.158325 0.0936073 -0.00835136 -0.161945 0.0871946 -0.00835136 -0.165947 0.0811471 0.00419604 -0.168923 0.0747547 0.00419604 -0.171589 0.0684123 0.00419604 -0.180794 0.0379056 0.00419604 -0.179454 0.043811 0.00419604 -0.179722 0.0438763 3.29648e-17 -0.177879 0.0498233 0.00419604 -0.176315 0.0560178 3.47135e-17 -0.17422 0.0622272 3.44209e-17 -0.182822 0.0264422 0.00419604 -0.182183 0.032162 3.44054e-17 -0.183813 0.0209255 3.16365e-17 -0.18435 0.0154972 3.27277e-17 -0.184656 0.00502559 0.00419604 -0.184444 0.010184 0.00419604 -0.184853 0 -0.00306226 -0.184719 -0.0101991 3.27083e-17 -0.180869 -0.00492252 -0.0163769 -0.181654 0 -0.014852 -0.182746 -0.0208042 -0.00835136 -0.182008 -0.0153003 -0.0124252 -0.181477 -0.0206597 -0.0124252 -0.180769 -0.0261452 -0.0124252 -0.182033 -0.026328 -0.00835136 -0.174075 -0.0553062 -0.0124252 -0.175292 -0.0556929 -0.00835136 -0.175881 -0.0492637 -0.0124252 -0.159012 -0.0940133 -0.00419604 -0.161945 -0.0871946 -0.00835136 -0.158325 -0.0936073 -0.00835136 -0.150682 -0.106855 -0.00419604 -0.154357 -0.100014 -0.00835136 -0.150031 -0.106394 -0.00835136 -0.145968 -0.11321 -0.00419604 -0.140876 -0.119487 -0.00419604 -0.135401 -0.125657 -0.00419604 -0.12954 -0.131692 -0.00419604 -0.123474 -0.137765 3.23476e-17 -0.109639 -0.148669 -0.00419604 -0.102252 -0.153843 -0.00419604 -0.0946458 -0.158957 3.37489e-17 -0.0779983 -0.16745 -0.00419604 -0.0692817 -0.17124 -0.00419604 -0.0602908 -0.174609 -0.00419604 -0.0510558 -0.177529 -0.00419604 -0.0416103 -0.179977 -0.00419604 -0.0222346 -0.183382 -0.00419604 -0.0318521 -0.181148 -0.00835136 -0.0221386 -0.18259 -0.00835136 -0.0123302 -0.183513 -0.00835136 -0.0124021 -0.184584 3.32692e-17 0.0173184 -0.183911 -0.00419604 0.0271269 -0.182722 -0.00419604 0.0368197 -0.181018 -0.00419604 0.0463572 -0.178813 -0.00419604 0.0554613 -0.175366 -0.00835136 0.0645388 -0.172232 -0.00835136 0.0649154 -0.173237 3.26778e-17 0.0822452 -0.165405 -0.00419604 0.0905012 -0.161036 -0.00419604 0.105991 -0.151291 -0.00419604 0.0979974 -0.155646 -0.00835136 0.105534 -0.150638 -0.00835136 0.113194 -0.14598 -0.00419604 0.126463 -0.134649 -0.00419604 0.119502 -0.139815 -0.00835136 0.125917 -0.134067 -0.00835136 0.132519 -0.128693 -0.00419604 0.138187 -0.122587 -0.00419604 0.14347 -0.11636 -0.00419604 0.148372 -0.110041 -0.00419604 0.1529 -0.103657 -0.00419604 0.157298 -0.0973778 3.38921e-17 0.161112 -0.0909278 3.3118e-17 0.167724 -0.0780619 3.28367e-17 0.170548 -0.071683 3.32728e-17 0.175302 -0.059112 3.39872e-17 0.177262 -0.0529459 3.19864e-17 0.178963 -0.046874 3.45098e-17 0.180421 -0.0409053 3.25369e-17 0.18165 -0.0350474 3.38061e-17 0.182664 -0.0293065 3.49819e-17 0.184103 -0.0181952 3.51192e-17 0.184554 -0.0128318 3.41922e-17 0.184844 -0.00759953 3.32879e-17 0.184983 -0.00249989 3.42068e-17 0.184983 0.00249989 3.44193e-17 0.183035 0.0180897 -0.00835136 0.183829 0.0181681 -0.00419604 0.183484 0.0127573 -0.00835136 0.184844 0.00759953 3.39654e-17 0.184554 0.0128318 3.15612e-17 0.184103 0.0181952 3.28823e-17 0.183477 0.0236878 3.22028e-17 0.182664 0.0293065 3.3526e-17 0.18165 0.0350474 3.38329e-17 0.180152 0.0408444 -0.00419604 0.178697 0.0468043 -0.00419604 0.177262 0.0529459 3.22496e-17 0.170294 0.0715763 -0.00419604 0.172065 0.0649826 -0.00835136 0.169558 0.0712672 -0.00835136 0.170548 0.071683 3.36868e-17 0.167474 0.0779456 -0.00419604 0.164338 0.0843569 -0.00419604 0.160872 0.0907924 -0.00419604 0.157064 0.0972328 -0.00419604 0.1529 0.103657 -0.00419604 0.148372 0.110041 -0.00419604 0.138187 0.122587 -0.00419604 0.14285 0.115857 -0.00835136 0.13759 0.122057 -0.00835136 0.132519 0.128693 -0.00419604 0.12002 0.140422 -0.00419604 0.125917 0.134067 -0.00835136 0.119502 0.139815 -0.00835136 0.113194 0.14598 -0.00419604 0.105991 0.151291 -0.00419604 0.0979974 0.155646 -0.00835136 0.0901103 0.160341 -0.00835136 0.0906361 0.161276 3.40805e-17 0.0736761 0.169396 -0.00419604 0.0648187 0.172979 -0.00419604 0.0557018 0.176126 -0.00419604 0.0463572 0.178813 -0.00419604 0.0368197 0.181018 -0.00419604 0.0173184 0.183911 -0.00419604 0.0270098 0.181933 -0.00835136 0.0172437 0.183117 -0.00835136 0.00740345 0.183778 -0.00835136 0.00744665 0.18485 3.24054e-17 -0.0222346 0.183382 -0.00419604 -0.0319903 0.181933 -0.00419604 -0.0416103 0.179977 -0.00419604 -0.0510558 0.177529 -0.00419604 -0.0600304 0.173855 -0.00835136 -0.0689825 0.170501 -0.00835136 -0.069385 0.171496 3.33747e-17 -0.0864138 0.163266 -0.00419604 -0.0945048 0.15872 -0.00419604 -0.102404 0.154072 3.41854e-17 -0.116655 0.14323 -0.00419604 -0.123474 0.137765 3.3316e-17 -0.140876 0.119487 -0.00419604 -0.134817 0.125114 -0.00835136 -0.140268 0.118971 -0.00835136 -0.150682 0.106855 -0.00419604 -0.145338 0.112721 -0.00835136 -0.150031 0.106394 -0.00835136 -0.150907 0.107015 3.36468e-17 -0.171845 0.0685143 3.40792e-17 -0.168923 0.0747547 -0.00419604 -0.171589 0.0684123 -0.00419604 -0.166194 0.0812681 3.32369e-17 -0.169175 0.0748662 3.36854e-17 -0.178144 0.0498976 3.38321e-17 -0.173961 0.0621345 -0.00419604 -0.176053 0.0559344 -0.00419604 -0.181063 0.0379621 3.31834e-17 -0.181912 0.0321141 -0.00419604 -0.181126 0.0319754 -0.00835136 -0.182822 0.0264422 -0.00419604 -0.183095 0.0264816 3.24901e-17 -0.183539 0.0208944 -0.00419604 -0.184075 0.0154741 -0.00419604 -0.184932 0.00503308 3.28443e-17 -0.184719 0.0101991 3.18629e-17 -0.177063 0 -0.022809 -0.178762 -0.00486518 -0.0201657 -0.17877 0 -0.0202607 -0.184444 -0.010184 -0.00419604 -0.184075 -0.0154741 -0.00419604 -0.183539 -0.0208944 -0.00419604 -0.182822 -0.0264422 -0.00419604 -0.181912 -0.0321141 -0.00419604 -0.179868 -0.0317534 -0.0124252 -0.180013 -0.0377419 -0.00835136 -0.181126 -0.0319754 -0.00835136 -0.177086 -0.0371282 -0.0163769 -0.177438 -0.0433189 -0.0124252 -0.178763 -0.0374798 -0.0124252 -0.177879 -0.0498233 -0.00419604 -0.176053 -0.0559344 -0.00419604 -0.165947 -0.0811471 -0.00419604 -0.162647 -0.0875728 -0.00419604 -0.155027 -0.100448 -0.00419604 -0.140268 -0.118971 -0.00835136 -0.144328 -0.111938 -0.0124252 -0.139294 -0.118144 -0.0124252 -0.134817 -0.125114 -0.00835136 -0.122758 -0.136966 -0.00835136 -0.128084 -0.130212 -0.0124252 -0.121905 -0.136015 -0.0124252 -0.116151 -0.142611 -0.00835136 -0.109166 -0.148027 -0.00835136 -0.0940967 -0.158034 -0.00835136 -0.101103 -0.152115 -0.0124252 -0.0934433 -0.156937 -0.0124252 -0.0860406 -0.162561 -0.00835136 -0.0776615 -0.166727 -0.00835136 -0.0689825 -0.170501 -0.00835136 -0.0600304 -0.173855 -0.00835136 -0.0414306 -0.1792 -0.00835136 -0.0504824 -0.175535 -0.0124252 -0.0411429 -0.177956 -0.0124252 -0.031631 -0.17989 -0.0124252 -0.0319903 -0.181933 -0.00419604 -0.00246871 -0.18391 -0.00835136 0.00740345 -0.183778 -0.00835136 0.0172437 -0.183117 -0.00835136 0.0270098 -0.181933 -0.00835136 0.0366607 -0.180236 -0.00835136 0.0458365 -0.176805 -0.0124252 0.0550761 -0.174148 -0.0124252 0.0557018 -0.176126 -0.00419604 0.0733579 -0.168664 -0.00835136 0.0818901 -0.164691 -0.00835136 0.0901103 -0.160341 -0.00835136 0.0984225 -0.156321 -0.00419604 0.112705 -0.14535 -0.00835136 0.12002 -0.140422 -0.00419604 0.13759 -0.122057 -0.00835136 0.13103 -0.127248 -0.0124252 0.136635 -0.12121 -0.0124252 0.14285 -0.115857 -0.00835136 0.155299 -0.0961407 -0.0124252 0.156385 -0.0968129 -0.00835136 0.151183 -0.102492 -0.0124252 0.157064 -0.0972328 -0.00419604 0.160178 -0.0904003 -0.00835136 0.163629 -0.0839926 -0.00835136 0.167474 -0.0779456 -0.00419604 0.173075 -0.058361 -0.0124252 0.174285 -0.0587691 -0.00835136 0.17087 -0.0645314 -0.0124252 0.175041 -0.059024 -0.00419604 0.176998 -0.0528671 -0.00419604 0.178697 -0.0468043 -0.00419604 0.180152 -0.0408444 -0.00419604 0.181379 -0.0349952 -0.00419604 0.183829 -0.0181681 -0.00419604 0.18428 -0.0128126 -0.00419604 0.184569 -0.00758822 -0.00419604 0.184708 -0.00249616 -0.00419604 0.184708 0.00249616 -0.00419604 0.184569 0.00758822 -0.00419604 0.18428 0.0128126 -0.00419604 0.183204 0.0236526 -0.00419604 0.182392 0.0292629 -0.00419604 0.181379 0.0349952 -0.00419604 0.17501 0.0522733 -0.0124252 0.176233 0.0526388 -0.00835136 0.17669 0.0462785 -0.0124252 0.176998 0.0528671 -0.00419604 0.175041 0.059024 -0.00419604 0.172811 0.0652645 -0.00419604 0.166751 0.077609 -0.00835136 0.163629 0.0839926 -0.00835136 0.160178 0.0904003 -0.00835136 0.156385 0.0968129 -0.00835136 0.15224 0.103209 -0.00835136 0.147731 0.109566 -0.00835136 0.14347 0.11636 -0.00419604 0.131947 0.128137 -0.00835136 0.126463 0.134649 -0.00419604 0.112705 0.14535 -0.00835136 0.104801 0.149592 -0.0124252 0.097317 0.154565 -0.0124252 0.0984225 0.156321 -0.00419604 0.0818901 0.164691 -0.00835136 0.0733579 0.168664 -0.00835136 0.0645388 0.172232 -0.00835136 0.0554613 0.175366 -0.00835136 0.0366607 0.180236 -0.00835136 0.0458365 0.176805 -0.0124252 0.0364061 0.178985 -0.0124252 0.0268222 0.18067 -0.0124252 0.0271269 0.182722 -0.00419604 -0.00246871 0.18391 -0.00835136 -0.0123302 0.183513 -0.00835136 -0.0221386 0.18259 -0.00835136 -0.0318521 0.181148 -0.00835136 -0.0414306 0.1792 -0.00835136 -0.0504824 0.175535 -0.0124252 -0.0596136 0.172647 -0.0124252 -0.0602908 0.174609 -0.00419604 -0.0776615 0.166727 -0.00835136 -0.0860406 0.162561 -0.00835136 -0.10181 0.153179 -0.00835136 -0.0934433 0.156937 -0.0124252 -0.101103 0.152115 -0.0124252 -0.109166 0.148027 -0.00835136 -0.122758 0.136966 -0.00835136 -0.115345 0.141621 -0.0124252 -0.121905 0.136015 -0.0124252 -0.12898 0.131123 -0.00835136 -0.135401 0.125657 -0.00419604 -0.145968 0.11321 -0.00419604 -0.154357 0.100014 -0.00835136 -0.165947 0.0811471 -0.00419604 -0.179454 0.043811 -0.00419604 -0.177879 0.0498233 -0.00419604 -0.17711 0.0496082 -0.00835136 -0.175292 0.0556929 -0.00835136 -0.17321 0.0618662 -0.00835136 -0.180794 0.0379056 -0.00419604 -0.182746 0.0208042 -0.00835136 -0.18328 0.0154073 -0.00835136 -0.184444 0.010184 -0.00419604 -0.184656 0.00502559 -0.00419604 -0.183647 -0.01014 -0.00835136 -0.18328 -0.0154073 -0.00835136 -0.178679 -0.0436218 -0.00835136 -0.17711 -0.0496082 -0.00835136 -0.168193 -0.0744319 -0.00835136 -0.16082 -0.0865891 -0.0124252 -0.157225 -0.0929573 -0.0124252 -0.153286 -0.09932 -0.0124252 -0.14899 -0.105655 -0.0124252 -0.145338 -0.112721 -0.00835136 -0.13388 -0.124245 -0.0124252 -0.12898 -0.131123 -0.00835136 -0.115345 -0.141621 -0.0124252 -0.107391 -0.14562 -0.0163769 -0.100155 -0.150688 -0.0163769 -0.10181 -0.153179 -0.00835136 -0.0854432 -0.161432 -0.0124252 -0.0771222 -0.165569 -0.0124252 -0.0685035 -0.169317 -0.0124252 -0.0590543 -0.171027 -0.0163769 -0.0500087 -0.173888 -0.0163769 -0.0508354 -0.176762 -0.00835136 -0.0219848 -0.181322 -0.0124252 -0.0122446 -0.182239 -0.0124252 -0.00245156 -0.182633 -0.0124252 0.00735204 -0.182502 -0.0124252 0.0171239 -0.181845 -0.0124252 0.0268222 -0.18067 -0.0124252 0.0360646 -0.177305 -0.0163769 0.0454064 -0.175146 -0.0163769 0.046157 -0.178041 -0.00835136 0.0640907 -0.171036 -0.0124252 0.0728485 -0.167493 -0.0124252 0.0813214 -0.163547 -0.0124252 0.097317 -0.154565 -0.0124252 0.088645 -0.157734 -0.0163769 0.0964039 -0.153115 -0.0163769 0.104801 -0.149592 -0.0124252 0.117559 -0.137542 -0.0163769 0.118672 -0.138844 -0.0124252 0.110873 -0.142986 -0.0163769 0.125043 -0.133136 -0.0124252 0.131947 -0.128137 -0.00835136 0.145329 -0.107784 -0.0163769 0.146705 -0.108805 -0.0124252 0.140527 -0.113973 -0.0163769 0.147731 -0.109566 -0.00835136 0.15224 -0.103209 -0.00835136 0.164039 -0.076347 -0.0163769 0.165593 -0.0770701 -0.0124252 0.160968 -0.0826267 -0.0163769 0.166751 -0.077609 -0.00835136 0.169558 -0.0712672 -0.00835136 0.172065 -0.0649826 -0.00835136 0.176233 -0.0526388 -0.00835136 0.177925 -0.0466021 -0.00835136 0.179374 -0.0406681 -0.00835136 0.180596 -0.0348441 -0.00835136 0.181604 -0.0291365 -0.00835136 0.182413 -0.0235504 -0.00835136 0.183035 -0.0180897 -0.00835136 0.183484 -0.0127573 -0.00835136 0.183772 -0.00755545 -0.00835136 0.18391 -0.00248538 -0.00835136 0.18391 0.00248538 -0.00835136 0.183772 0.00755545 -0.00835136 0.182413 0.0235504 -0.00835136 0.181764 0.0179641 -0.0124252 0.181146 0.0233869 -0.0124252 0.181604 0.0291365 -0.00835136 0.180596 0.0348441 -0.00835136 0.179374 0.0406681 -0.00835136 0.177925 0.0466021 -0.00835136 0.174285 0.0587691 -0.00835136 0.17087 0.0645314 -0.0124252 0.168381 0.0707723 -0.0124252 0.157573 0.0889303 -0.0163769 0.159065 0.0897726 -0.0124252 0.160968 0.0826267 -0.0163769 0.149764 0.101531 -0.0163769 0.151183 0.102492 -0.0124252 0.153842 0.0952386 -0.0163769 0.140527 0.113973 -0.0163769 0.141858 0.115053 -0.0124252 0.145329 0.107784 -0.0163769 0.136635 0.12121 -0.0124252 0.125043 0.133136 -0.0124252 0.129801 0.126054 -0.0163769 0.123869 0.131887 -0.0163769 0.118672 0.138844 -0.0124252 0.111923 0.144341 -0.0124252 0.105534 0.150638 -0.00835136 0.0894846 0.159228 -0.0124252 0.0813214 0.163547 -0.0124252 0.0728485 0.167493 -0.0124252 0.0550761 0.174148 -0.0124252 0.0634893 0.169431 -0.0163769 0.0545594 0.172514 -0.0163769 0.0454064 0.175146 -0.0163769 0.046157 0.178041 -0.00835136 0.0171239 0.181845 -0.0124252 0.00735204 0.182502 -0.0124252 -0.00245156 0.182633 -0.0124252 -0.0122446 0.182239 -0.0124252 -0.0219848 0.181322 -0.0124252 -0.031631 0.17989 -0.0124252 -0.0407568 0.176286 -0.0163769 -0.0500087 0.173888 -0.0163769 -0.0508354 0.176762 -0.00835136 -0.0685035 0.169317 -0.0124252 -0.0771222 0.165569 -0.0124252 -0.0925666 0.155465 -0.0163769 -0.0846415 0.159918 -0.0163769 -0.0940967 0.158034 -0.00835136 -0.108408 0.146999 -0.0124252 -0.116151 0.142611 -0.00835136 -0.128084 0.130212 -0.0124252 -0.13388 0.124245 -0.0124252 -0.139294 0.118144 -0.0124252 -0.144328 0.111938 -0.0124252 -0.14899 0.105655 -0.0124252 -0.15575 0.0920851 -0.0163769 -0.168193 0.0744319 -0.00835136 -0.170848 0.0681168 -0.00835136 -0.157225 0.0929573 -0.0124252 -0.178763 0.0374798 -0.0124252 -0.179868 0.0317534 -0.0124252 -0.178679 0.0436218 -0.00835136 -0.172007 0.0614366 -0.0124252 -0.174075 0.0553062 -0.0124252 -0.180013 0.0377419 -0.00835136 -0.182033 0.026328 -0.00835136 -0.181477 0.0206597 -0.0124252 -0.182008 0.0153003 -0.0124252 -0.183859 0.00500389 -0.00835136 -0.183647 0.01014 -0.00835136 -0.17102 0 -0.0297296 -0.17354 -0.00472304 -0.0270916 -0.17318 0 -0.0275526 -0.182372 -0.0100696 -0.0124252 -0.176305 -0.0047983 -0.0237508 -0.175197 0 -0.0252426 -0.177681 -0.0202275 -0.0201657 -0.179775 -0.0204659 -0.0163769 -0.1782 -0.0149802 -0.0201657 -0.176987 -0.0255982 -0.0201657 -0.179073 -0.0258999 -0.0163769 -0.17423 -0.0488015 -0.0163769 -0.175774 -0.0429124 -0.0163769 -0.173726 -0.0424126 -0.0201657 -0.165458 -0.0732215 -0.0163769 -0.162543 -0.0794828 -0.0163769 -0.150079 -0.0972421 -0.0201657 -0.151847 -0.0983881 -0.0163769 -0.153936 -0.0910126 -0.0201657 -0.147592 -0.104664 -0.0163769 -0.142974 -0.110888 -0.0163769 -0.137987 -0.117036 -0.0163769 -0.125405 -0.127488 -0.0201657 -0.126883 -0.128991 -0.0163769 -0.13108 -0.121646 -0.0201657 -0.120761 -0.134739 -0.0163769 -0.112932 -0.138658 -0.0201657 -0.10614 -0.143923 -0.0201657 -0.108408 -0.146999 -0.0124252 -0.0925666 -0.155465 -0.0163769 -0.0846415 -0.159918 -0.0163769 -0.0763986 -0.164015 -0.0163769 -0.0583664 -0.169035 -0.0201657 -0.0670704 -0.165775 -0.0201657 -0.0596136 -0.172647 -0.0124252 -0.0407568 -0.176286 -0.0163769 -0.0313342 -0.178202 -0.0163769 -0.0217786 -0.17962 -0.0163769 -0.0121297 -0.180529 -0.0163769 -0.00242856 -0.18092 -0.0163769 0.00728306 -0.180789 -0.0163769 0.0169633 -0.180139 -0.0163769 0.0262611 -0.17689 -0.0201657 0.0356445 -0.17524 -0.0201657 0.0364061 -0.178985 -0.0124252 0.0545594 -0.172514 -0.0163769 0.0634893 -0.169431 -0.0163769 0.072165 -0.165922 -0.0163769 0.0876125 -0.155896 -0.0201657 0.0796201 -0.160126 -0.0201657 0.0894846 -0.159228 -0.0124252 0.103818 -0.148188 -0.0163769 0.111923 -0.144341 -0.0124252 0.123869 -0.131887 -0.0163769 0.129801 -0.126054 -0.0163769 0.135353 -0.120073 -0.0163769 0.141858 -0.115053 -0.0124252 0.149764 -0.101531 -0.0163769 0.153842 -0.0952386 -0.0163769 0.159065 -0.0897726 -0.0124252 0.162492 -0.0834093 -0.0124252 0.168381 -0.0707723 -0.0124252 0.171348 -0.0511797 -0.0201657 0.173368 -0.0517828 -0.0163769 0.169454 -0.0571401 -0.0201657 0.17501 -0.0522733 -0.0124252 0.17669 -0.0462785 -0.0124252 0.178129 -0.0403857 -0.0124252 0.179342 -0.0346022 -0.0124252 0.180343 -0.0289342 -0.0124252 0.181146 -0.0233869 -0.0124252 0.181764 -0.0179641 -0.0124252 0.18221 -0.0126687 -0.0124252 0.182496 -0.00750298 -0.0124252 0.182633 -0.00246813 -0.0124252 0.182633 0.00246813 -0.0124252 0.182496 0.00750298 -0.0124252 0.18221 0.0126687 -0.0124252 0.17559 0.0338783 -0.0201657 0.174143 0.0279395 -0.0237508 0.173176 0.0334125 -0.0237508 0.180343 0.0289342 -0.0124252 0.179342 0.0346022 -0.0124252 0.178129 0.0403857 -0.0124252 0.169454 0.0571401 -0.0201657 0.171451 0.0578135 -0.0163769 0.171348 0.0511797 -0.0201657 0.173075 0.058361 -0.0124252 0.162129 0.0754578 -0.0201657 0.164039 0.076347 -0.0163769 0.164858 0.0692917 -0.0201657 0.165593 0.0770701 -0.0124252 0.162492 0.0834093 -0.0124252 0.155299 0.0961407 -0.0124252 0.146705 0.108805 -0.0124252 0.135353 0.120073 -0.0163769 0.13103 0.127248 -0.0124252 0.117559 0.137542 -0.0163769 0.102608 0.146462 -0.0201657 0.103818 0.148188 -0.0163769 0.109581 0.141321 -0.0201657 0.0964039 0.153115 -0.0163769 0.088645 0.157734 -0.0163769 0.0805584 0.162013 -0.0163769 0.0713245 0.163989 -0.0201657 0.0627498 0.167458 -0.0201657 0.0640907 0.171036 -0.0124252 0.0360646 0.177305 -0.0163769 0.0265706 0.178974 -0.0163769 0.0169633 0.180139 -0.0163769 0.00728306 0.180789 -0.0163769 -0.00242856 0.18092 -0.0163769 -0.0121297 0.180529 -0.0163769 -0.0215249 0.177528 -0.0201657 -0.0309692 0.176126 -0.0201657 -0.0313342 0.178202 -0.0163769 -0.0402821 0.174233 -0.0201657 -0.0411429 0.177956 -0.0124252 -0.0590543 0.171027 -0.0163769 -0.0678608 0.167728 -0.0163769 -0.0763986 0.164015 -0.0163769 -0.0854432 0.161432 -0.0124252 -0.100155 0.150688 -0.0163769 -0.112932 0.138658 -0.0201657 -0.114262 0.140292 -0.0163769 -0.10614 0.143923 -0.0201657 -0.120761 0.134739 -0.0163769 -0.13108 0.121646 -0.0201657 -0.132624 0.12308 -0.0163769 -0.125405 0.127488 -0.0201657 -0.141309 0.109597 -0.0201657 -0.142974 0.110888 -0.0163769 -0.13638 0.115673 -0.0201657 -0.150079 0.0972421 -0.0201657 -0.151847 0.0983881 -0.0163769 -0.145873 0.103445 -0.0201657 -0.153286 0.09932 -0.0124252 -0.169662 0.0676438 -0.0124252 -0.175881 0.0492637 -0.0124252 -0.177438 0.0433189 -0.0124252 -0.172442 0.0547872 -0.0163769 -0.170393 0.0608602 -0.0163769 -0.180769 0.0261452 -0.0124252 -0.178181 0.0314555 -0.0163769 -0.179775 0.0204659 -0.0163769 -0.1803 0.0151568 -0.0163769 -0.182582 0.00496914 -0.0124252 -0.182372 0.0100696 -0.0124252 -0.180304 0 -0.0176057 -0.180661 -0.00997508 -0.0163769 -0.1803 -0.0151568 -0.0163769 -0.178181 -0.0314555 -0.0163769 -0.173685 -0.0306617 -0.0237508 -0.175023 -0.0366957 -0.0201657 -0.176105 -0.0310891 -0.0201657 -0.169834 -0.04757 -0.0237508 -0.155291 -0.0836122 -0.0237508 -0.157456 -0.0847776 -0.0201657 -0.158442 -0.0774771 -0.0237508 -0.159312 -0.0857767 -0.0163769 -0.15575 -0.0920851 -0.0163769 -0.139366 -0.10809 -0.0237508 -0.141309 -0.109597 -0.0201657 -0.143867 -0.102023 -0.0237508 -0.13638 -0.115673 -0.0201657 -0.132624 -0.12308 -0.0163769 -0.119355 -0.133169 -0.0201657 -0.114262 -0.140292 -0.0163769 -0.0989883 -0.148933 -0.0201657 -0.0914884 -0.153654 -0.0201657 -0.0836556 -0.158055 -0.0201657 -0.0744708 -0.159877 -0.0237508 -0.0661484 -0.163496 -0.0237508 -0.0678608 -0.167728 -0.0163769 -0.0494262 -0.171862 -0.0201657 -0.0402821 -0.174233 -0.0201657 -0.0309692 -0.176126 -0.0201657 -0.0215249 -0.177528 -0.0201657 -0.0119884 -0.178426 -0.0201657 -0.00240027 -0.178812 -0.0201657 0.00709928 -0.176227 -0.0237508 0.0165352 -0.175593 -0.0237508 0.0167657 -0.178041 -0.0201657 0.0259001 -0.174458 -0.0237508 0.0265706 -0.178974 -0.0163769 0.0448775 -0.173106 -0.0201657 0.0539239 -0.170505 -0.0201657 0.0627498 -0.167458 -0.0201657 0.070344 -0.161735 -0.0237508 0.0785256 -0.157925 -0.0237508 0.0805584 -0.162013 -0.0163769 0.095281 -0.151331 -0.0201657 0.101198 -0.144449 -0.0237508 0.108075 -0.139378 -0.0237508 0.109581 -0.141321 -0.0201657 0.11619 -0.13594 -0.0201657 0.120744 -0.128559 -0.0237508 0.126526 -0.122873 -0.0237508 0.128289 -0.124585 -0.0201657 0.133776 -0.118674 -0.0201657 0.13889 -0.112646 -0.0201657 0.143636 -0.106528 -0.0201657 0.153597 -0.0866862 -0.0237508 0.155738 -0.0878945 -0.0201657 0.14996 -0.0928354 -0.0237508 0.157573 -0.0889303 -0.0163769 0.159093 -0.0816643 -0.0201657 0.162129 -0.0754578 -0.0201657 0.166801 -0.0701083 -0.0163769 0.169267 -0.0639259 -0.0163769 0.171451 -0.0578135 -0.0163769 0.175032 -0.0458443 -0.0163769 0.176458 -0.0400067 -0.0163769 0.177659 -0.0342775 -0.0163769 0.178651 -0.0286627 -0.0163769 0.179447 -0.0231674 -0.0163769 0.180059 -0.0177955 -0.0163769 0.1805 -0.0125499 -0.0163769 0.180783 -0.00743258 -0.0163769 0.180919 -0.00244497 -0.0163769 0.180919 0.00244497 -0.0163769 0.180783 0.00743258 -0.0163769 0.1805 0.0125499 -0.0163769 0.180059 0.0177955 -0.0163769 0.179447 0.0231674 -0.0163769 0.178651 0.0286627 -0.0163769 0.177659 0.0342775 -0.0163769 0.176458 0.0400067 -0.0163769 0.175032 0.0458443 -0.0163769 0.173368 0.0517828 -0.0163769 0.169267 0.0639259 -0.0163769 0.166801 0.0701083 -0.0163769 0.159093 0.0816643 -0.0201657 0.155738 0.0878945 -0.0201657 0.15205 0.0941293 -0.0201657 0.14802 0.100348 -0.0201657 0.143636 0.106528 -0.0201657 0.13889 0.112646 -0.0201657 0.131937 0.117043 -0.0237508 0.126526 0.122873 -0.0237508 0.128289 0.124585 -0.0201657 0.122427 0.130351 -0.0201657 0.114592 0.134071 -0.0237508 0.108075 0.139378 -0.0237508 0.110873 0.142986 -0.0163769 0.095281 0.151331 -0.0201657 0.0876125 0.155896 -0.0201657 0.0785256 0.157925 -0.0237508 0.070344 0.161735 -0.0237508 0.072165 0.165922 -0.0163769 0.0539239 0.170505 -0.0201657 0.0448775 0.173106 -0.0201657 0.0356445 0.17524 -0.0201657 0.0262611 0.17689 -0.0201657 0.0167657 0.178041 -0.0201657 0.00719823 0.178684 -0.0201657 -0.00236728 0.176354 -0.0237508 -0.0118236 0.175973 -0.0237508 -0.0119884 0.178426 -0.0201657 -0.021229 0.175088 -0.0237508 -0.0217786 0.17962 -0.0163769 -0.0494262 0.171862 -0.0201657 -0.0583664 0.169035 -0.0201657 -0.0670704 0.165775 -0.0201657 -0.0744708 0.159877 -0.0237508 -0.0825056 0.155882 -0.0237508 -0.0836556 0.158055 -0.0201657 -0.0914884 0.153654 -0.0201657 -0.0989883 0.148933 -0.0201657 -0.107391 0.14562 -0.0163769 -0.119355 0.133169 -0.0201657 -0.126883 0.128991 -0.0163769 -0.137987 0.117036 -0.0163769 -0.147592 0.104664 -0.0163769 -0.153936 0.0910126 -0.0201657 -0.157456 0.0847776 -0.0201657 -0.16065 0.078557 -0.0201657 -0.17423 0.0488015 -0.0163769 -0.175774 0.0429124 -0.0163769 -0.170433 0.0541491 -0.0201657 -0.168409 0.0601513 -0.0201657 -0.177086 0.0371282 -0.0163769 -0.179073 0.0258999 -0.0163769 -0.176105 0.0310891 -0.0201657 -0.177681 0.0202275 -0.0201657 -0.1782 0.0149802 -0.0201657 -0.180869 0.00492252 -0.0163769 -0.180661 0.00997508 -0.0163769 -0.178557 -0.0098589 -0.0201657 -0.167257 -0.00455206 -0.0328772 -0.170509 -0.00464057 -0.0301473 -0.168724 0 -0.0317613 -0.17249 -0.0196365 -0.0270916 -0.169973 -0.0142886 -0.0301473 -0.169478 -0.0192936 -0.0301473 -0.166943 -0.0350016 -0.0301473 -0.168651 -0.0411735 -0.0270916 -0.16991 -0.0356236 -0.0270916 -0.172201 -0.0482331 -0.0201657 -0.163829 -0.0653183 -0.0237508 -0.163531 -0.0723687 -0.0201657 -0.16065 -0.078557 -0.0201657 -0.15182 -0.0897614 -0.0237508 -0.148016 -0.0959054 -0.0237508 -0.145873 -0.103445 -0.0201657 -0.132395 -0.112293 -0.0270916 -0.12725 -0.118092 -0.0270916 -0.129278 -0.119974 -0.0237508 -0.123681 -0.125736 -0.0237508 -0.115868 -0.129279 -0.0270916 -0.109632 -0.134607 -0.0270916 -0.111379 -0.136752 -0.0237508 -0.104681 -0.141945 -0.0237508 -0.0976275 -0.146885 -0.0237508 -0.0902308 -0.151542 -0.0237508 -0.0812116 -0.153437 -0.0270916 -0.0733028 -0.157369 -0.0270916 -0.0755088 -0.162105 -0.0201657 -0.0575641 -0.166712 -0.0237508 -0.0487468 -0.1695 -0.0237508 -0.0397284 -0.171837 -0.0237508 -0.0305435 -0.173705 -0.0237508 -0.021229 -0.175088 -0.0237508 -0.0116382 -0.173213 -0.0270916 -0.00233015 -0.173588 -0.0270916 -0.00236728 -0.176354 -0.0237508 0.00698793 -0.173463 -0.0270916 0.00719823 -0.178684 -0.0201657 0.0351545 -0.172831 -0.0237508 0.0442606 -0.170726 -0.0237508 0.0531826 -0.168161 -0.0237508 0.0618873 -0.165156 -0.0237508 0.0713245 -0.163989 -0.0201657 0.0864082 -0.153753 -0.0237508 0.0939712 -0.149251 -0.0237508 0.102608 -0.146462 -0.0201657 0.114592 -0.134071 -0.0237508 0.122427 -0.130351 -0.0201657 0.129868 -0.115207 -0.0270916 0.134833 -0.109355 -0.0270916 0.136981 -0.111097 -0.0237508 0.13944 -0.103416 -0.0270916 0.143695 -0.0974165 -0.0270916 0.145985 -0.0989687 -0.0237508 0.14802 -0.100348 -0.0201657 0.15205 -0.0941293 -0.0201657 0.160042 -0.0672673 -0.0270916 0.162592 -0.0683392 -0.0237508 0.157392 -0.0732532 -0.0270916 0.164858 -0.0692917 -0.0201657 0.167295 -0.0631813 -0.0201657 0.167939 -0.0439866 -0.0270916 0.170615 -0.0446875 -0.0237508 0.166342 -0.0496845 -0.0270916 0.172993 -0.0453104 -0.0201657 0.174402 -0.0395408 -0.0201657 0.17559 -0.0338783 -0.0201657 0.17657 -0.0283289 -0.0201657 0.177357 -0.0228976 -0.0201657 0.177961 -0.0175882 -0.0201657 0.178398 -0.0124037 -0.0201657 0.178678 -0.00734601 -0.0201657 0.178812 -0.00241649 -0.0201657 0.178812 0.00241649 -0.0201657 0.178678 0.00734601 -0.0201657 0.178398 0.0124037 -0.0201657 0.177961 0.0175882 -0.0201657 0.177357 0.0228976 -0.0201657 0.17657 0.0283289 -0.0201657 0.174402 0.0395408 -0.0201657 0.172993 0.0453104 -0.0201657 0.168993 0.0504761 -0.0237508 0.167125 0.0563546 -0.0237508 0.167295 0.0631813 -0.0201657 0.162592 0.0683392 -0.0237508 0.1599 0.0744205 -0.0237508 0.151188 0.0853266 -0.0270916 0.147608 0.0913793 -0.0270916 0.14996 0.0928354 -0.0237508 0.143695 0.0974165 -0.0270916 0.13944 0.103416 -0.0270916 0.141662 0.105064 -0.0237508 0.136981 0.111097 -0.0237508 0.133776 0.118674 -0.0201657 0.120744 0.128559 -0.0237508 0.11619 0.13594 -0.0201657 0.101198 0.144449 -0.0237508 0.0939712 0.149251 -0.0237508 0.0850529 0.151342 -0.0270916 0.077294 0.155448 -0.0270916 0.0796201 0.160126 -0.0201657 0.0618873 0.165156 -0.0237508 0.0531826 0.168161 -0.0237508 0.0442606 0.170726 -0.0237508 0.0351545 0.172831 -0.0237508 0.0259001 0.174458 -0.0237508 0.0162759 0.172839 -0.0270916 0.00698793 0.173463 -0.0270916 0.00709928 0.176227 -0.0237508 -0.00233015 0.173588 -0.0270916 -0.00240027 0.178812 -0.0201657 -0.0305435 0.173705 -0.0237508 -0.0397284 0.171837 -0.0237508 -0.0487468 0.1695 -0.0237508 -0.0575641 0.166712 -0.0237508 -0.0651109 0.160931 -0.0270916 -0.0733028 0.157369 -0.0270916 -0.0755088 0.162105 -0.0201657 -0.0902308 0.151542 -0.0237508 -0.0960963 0.144582 -0.0270916 -0.103039 0.139719 -0.0270916 -0.104681 0.141945 -0.0237508 -0.111379 0.136752 -0.0237508 -0.115868 0.129279 -0.0270916 -0.121741 0.123764 -0.0270916 -0.123681 0.125736 -0.0237508 -0.129278 0.119974 -0.0237508 -0.134505 0.114083 -0.0237508 -0.139366 0.10809 -0.0237508 -0.143867 0.102023 -0.0237508 -0.148016 0.0959054 -0.0237508 -0.152856 0.0823008 -0.0270916 -0.155957 0.0762619 -0.0270916 -0.15182 0.0897614 -0.0237508 -0.172201 0.0482331 -0.0201657 -0.173726 0.0424126 -0.0201657 -0.166094 0.0593244 -0.0237508 -0.16809 0.0534047 -0.0237508 -0.175023 0.0366957 -0.0201657 -0.176987 0.0255982 -0.0201657 -0.17575 0.0147743 -0.0237508 -0.178557 0.0098589 -0.0201657 -0.175238 0.0199494 -0.0237508 -0.178762 0.00486518 -0.0201657 -0.161064 0 -0.0368271 -0.163825 -0.00445866 -0.0352405 -0.16374 0 -0.0353297 -0.176102 -0.00972337 -0.0237508 -0.17575 -0.0147743 -0.0237508 -0.175238 -0.0199494 -0.0237508 -0.174554 -0.0252463 -0.0237508 -0.166245 -0.0189256 -0.0328772 -0.165596 -0.0239507 -0.0328772 -0.168816 -0.0244164 -0.0301473 -0.172617 -0.0361913 -0.0237508 -0.171338 -0.0418296 -0.0237508 -0.158444 -0.0631711 -0.0301473 -0.155981 -0.0690277 -0.0301473 -0.158753 -0.0702544 -0.0270916 -0.161283 -0.0713739 -0.0237508 -0.155957 -0.0762619 -0.0270916 -0.152856 -0.0823008 -0.0270916 -0.149439 -0.0883536 -0.0270916 -0.145694 -0.0944012 -0.0270916 -0.141611 -0.100422 -0.0270916 -0.137181 -0.106395 -0.0270916 -0.134505 -0.114083 -0.0237508 -0.121741 -0.123764 -0.0270916 -0.117714 -0.131339 -0.0237508 -0.103039 -0.139719 -0.0270916 -0.0960963 -0.144582 -0.0270916 -0.0872647 -0.14656 -0.0301473 -0.0797935 -0.150758 -0.0301473 -0.0825056 -0.155882 -0.0237508 -0.0651109 -0.160931 -0.0270916 -0.0566612 -0.164097 -0.0270916 -0.0479822 -0.166841 -0.0270916 -0.0391053 -0.169142 -0.0270916 -0.0295395 -0.167995 -0.0301473 -0.0205312 -0.169332 -0.0301473 -0.0208961 -0.172342 -0.0270916 -0.0114349 -0.170189 -0.0301473 -0.0118236 -0.175973 -0.0237508 0.0162759 -0.172839 -0.0270916 0.0254939 -0.171722 -0.0270916 0.0346031 -0.17012 -0.0270916 0.0435664 -0.168049 -0.0270916 0.0514344 -0.162633 -0.0301473 0.0598529 -0.159727 -0.0301473 0.0609166 -0.162565 -0.0270916 0.0680317 -0.156418 -0.0301473 0.0692407 -0.159198 -0.0270916 0.077294 -0.155448 -0.0270916 0.0850529 -0.151342 -0.0270916 0.0908822 -0.144345 -0.0301473 0.0978714 -0.1397 -0.0301473 0.0996107 -0.142183 -0.0270916 0.10638 -0.137192 -0.0270916 0.112795 -0.131968 -0.0270916 0.11885 -0.126543 -0.0270916 0.124541 -0.120946 -0.0270916 0.131937 -0.117043 -0.0237508 0.141662 -0.105064 -0.0237508 0.147608 -0.0913793 -0.0270916 0.151188 -0.0853266 -0.0270916 0.156906 -0.0805417 -0.0237508 0.1599 -0.0744205 -0.0237508 0.164996 -0.0623128 -0.0237508 0.167125 -0.0563546 -0.0237508 0.168993 -0.0504761 -0.0237508 0.172005 -0.0389972 -0.0237508 0.173176 -0.0334125 -0.0237508 0.174143 -0.0279395 -0.0237508 0.174918 -0.0225828 -0.0237508 0.175515 -0.0173465 -0.0237508 0.175945 -0.0122332 -0.0237508 0.176221 -0.00724503 -0.0237508 0.176354 -0.00238327 -0.0237508 0.176354 0.00238327 -0.0237508 0.176221 0.00724503 -0.0237508 0.175945 0.0122332 -0.0237508 0.175515 0.0173465 -0.0237508 0.174918 0.0225828 -0.0237508 0.166351 0.0377153 -0.0301473 0.163178 0.0369959 -0.0328772 0.165007 0.0432185 -0.0301473 0.172005 0.0389972 -0.0237508 0.170615 0.0446875 -0.0237508 0.161631 0.0545021 -0.0301473 0.159572 0.0602645 -0.0301473 0.162408 0.0613355 -0.0270916 0.164996 0.0623128 -0.0237508 0.154644 0.0719741 -0.0301473 0.151748 0.0778942 -0.0301473 0.154445 0.0792785 -0.0270916 0.156906 0.0805417 -0.0237508 0.153597 0.0866862 -0.0237508 0.145985 0.0989687 -0.0237508 0.132478 0.107445 -0.0301473 0.1276 0.113195 -0.0301473 0.129868 0.115207 -0.0270916 0.124541 0.120946 -0.0270916 0.116775 0.124333 -0.0301473 0.110826 0.129664 -0.0301473 0.112795 0.131968 -0.0270916 0.10638 0.137192 -0.0270916 0.0996107 0.142183 -0.0270916 0.0908822 0.144345 -0.0301473 0.0835678 0.148699 -0.0301473 0.0864082 0.153753 -0.0237508 0.0692407 0.159198 -0.0270916 0.0609166 0.162565 -0.0270916 0.0523485 0.165523 -0.0270916 0.0435664 0.168049 -0.0270916 0.0339989 0.16715 -0.0301473 0.0250487 0.168723 -0.0301473 0.0254939 0.171722 -0.0270916 0.0159917 0.169821 -0.0301473 0.0165352 0.175593 -0.0237508 -0.0116382 0.173213 -0.0270916 -0.0208961 0.172342 -0.0270916 -0.0300645 0.170981 -0.0270916 -0.0391053 0.169142 -0.0270916 -0.0479822 0.166841 -0.0270916 -0.0556719 0.161232 -0.0301473 -0.063974 0.158121 -0.0301473 -0.0661484 0.163496 -0.0237508 -0.0812116 0.153437 -0.0270916 -0.0888156 0.149165 -0.0270916 -0.0976275 0.146885 -0.0237508 -0.109632 0.134607 -0.0270916 -0.117714 0.131339 -0.0237508 -0.12725 0.118092 -0.0270916 -0.132395 0.112293 -0.0270916 -0.137181 0.106395 -0.0270916 -0.141611 0.100422 -0.0270916 -0.145694 0.0944012 -0.0270916 -0.155291 0.0836122 -0.0237508 -0.162565 0.0516492 -0.0301473 -0.164251 0.0460063 -0.0301473 -0.149439 0.0883536 -0.0270916 -0.169834 0.04757 -0.0237508 -0.171338 0.0418296 -0.0237508 -0.165454 0.0525671 -0.0270916 -0.163488 0.058394 -0.0270916 -0.173685 0.0306617 -0.0237508 -0.172617 0.0361913 -0.0237508 -0.174554 0.0252463 -0.0237508 -0.17096 0.0301808 -0.0270916 -0.17249 0.0196365 -0.0270916 -0.172994 0.0145426 -0.0270916 -0.176102 0.00972337 -0.0237508 -0.176305 0.0047983 -0.0237508 -0.17334 -0.00957087 -0.0270916 -0.172994 -0.0145426 -0.0270916 -0.171816 -0.0248504 -0.0270916 -0.17096 -0.0301808 -0.0270916 -0.163488 -0.058394 -0.0270916 -0.16126 -0.0642938 -0.0270916 -0.146829 -0.0868108 -0.0301473 -0.150187 -0.0808637 -0.0301473 -0.147322 -0.0793213 -0.0328772 -0.139138 -0.0986689 -0.0301473 -0.14315 -0.0927528 -0.0301473 -0.14042 -0.0909836 -0.0328772 -0.134785 -0.104537 -0.0301473 -0.130084 -0.110333 -0.0301473 -0.125028 -0.11603 -0.0301473 -0.113845 -0.127021 -0.0301473 -0.119615 -0.121603 -0.0301473 -0.117334 -0.119283 -0.0328772 -0.107718 -0.132257 -0.0301473 -0.10124 -0.137279 -0.0301473 -0.0944183 -0.142057 -0.0301473 -0.0926173 -0.139347 -0.0328772 -0.0888156 -0.149165 -0.0270916 -0.0720228 -0.154621 -0.0301473 -0.063974 -0.158121 -0.0301473 -0.0556719 -0.161232 -0.0301473 -0.0384224 -0.166189 -0.0301473 -0.0471444 -0.163928 -0.0301473 -0.0462451 -0.160801 -0.0328772 -0.0376896 -0.163019 -0.0328772 -0.0300645 -0.170981 -0.0270916 -0.00228946 -0.170557 -0.0301473 0.00686591 -0.170434 -0.0301473 0.0159917 -0.169821 -0.0301473 0.0250487 -0.168723 -0.0301473 0.0339989 -0.16715 -0.0301473 0.0428057 -0.165114 -0.0301473 0.0419892 -0.161965 -0.0328772 0.0523485 -0.165523 -0.0270916 0.0759443 -0.152733 -0.0301473 0.0835678 -0.148699 -0.0301473 0.0924973 -0.14691 -0.0270916 0.104522 -0.134797 -0.0301473 0.116775 -0.124333 -0.0301473 0.110826 -0.129664 -0.0301473 0.108712 -0.127191 -0.0328772 0.122366 -0.118834 -0.0301473 0.1276 -0.113195 -0.0301473 0.132478 -0.107445 -0.0301473 0.137005 -0.10161 -0.0301473 0.141186 -0.0957154 -0.0301473 0.145031 -0.0897837 -0.0301473 0.148548 -0.0838367 -0.0301473 0.154445 -0.0792785 -0.0270916 0.154644 -0.0719741 -0.0301473 0.157247 -0.0660928 -0.0301473 0.162408 -0.0613355 -0.0270916 0.164503 -0.0554707 -0.0270916 0.164289 -0.0316978 -0.0328772 0.160918 -0.0310475 -0.0352405 0.165206 -0.0265056 -0.0328772 0.169307 -0.0383856 -0.0270916 0.17046 -0.0328885 -0.0270916 0.171412 -0.0275013 -0.0270916 0.172175 -0.0222286 -0.0270916 0.172762 -0.0170744 -0.0270916 0.173186 -0.0120413 -0.0270916 0.173457 -0.0071314 -0.0270916 0.173588 -0.00234589 -0.0270916 0.173588 0.00234589 -0.0270916 0.173457 0.0071314 -0.0270916 0.173186 0.0120413 -0.0270916 0.172762 0.0170744 -0.0270916 0.172175 0.0222286 -0.0270916 0.171412 0.0275013 -0.0270916 0.17046 0.0328885 -0.0270916 0.169307 0.0383856 -0.0270916 0.167939 0.0439866 -0.0270916 0.166342 0.0496845 -0.0270916 0.164503 0.0554707 -0.0270916 0.160042 0.0672673 -0.0270916 0.157392 0.0732532 -0.0270916 0.148548 0.0838367 -0.0301473 0.145031 0.0897837 -0.0301473 0.141186 0.0957154 -0.0301473 0.137005 0.10161 -0.0301473 0.134833 0.109355 -0.0270916 0.122366 0.118834 -0.0301473 0.11885 0.126543 -0.0270916 0.104522 0.134797 -0.0301473 0.0978714 0.1397 -0.0301473 0.0960045 0.137036 -0.0328772 0.0924973 0.14691 -0.0270916 0.0759443 0.152733 -0.0301473 0.0680317 0.156418 -0.0301473 0.0598529 0.159727 -0.0301473 0.0514344 0.162633 -0.0301473 0.0428057 0.165114 -0.0301473 0.0419892 0.161965 -0.0328772 0.0346031 0.17012 -0.0270916 0.00686591 0.170434 -0.0301473 -0.00228946 0.170557 -0.0301473 -0.0114349 0.170189 -0.0301473 -0.0205312 0.169332 -0.0301473 -0.0295395 0.167995 -0.0301473 -0.0384224 0.166189 -0.0301473 -0.0471444 0.163928 -0.0301473 -0.0462451 0.160801 -0.0328772 -0.0566612 0.164097 -0.0270916 -0.0720228 0.154621 -0.0301473 -0.0797935 0.150758 -0.0301473 -0.0944183 0.142057 -0.0301473 -0.0872647 0.14656 -0.0301473 -0.0856002 0.143765 -0.0328772 -0.10124 0.137279 -0.0301473 -0.107718 0.132257 -0.0301473 -0.113845 0.127021 -0.0301473 -0.119615 0.121603 -0.0301473 -0.130084 0.110333 -0.0301473 -0.125028 0.11603 -0.0301473 -0.122643 0.113817 -0.0328772 -0.139138 0.0986689 -0.0301473 -0.134785 0.104537 -0.0301473 -0.132214 0.102543 -0.0328772 -0.146829 0.0868108 -0.0301473 -0.14315 0.0927528 -0.0301473 -0.14042 0.0909836 -0.0328772 -0.153233 0.0749303 -0.0301473 -0.16717 0.0468239 -0.0270916 -0.168651 0.0411735 -0.0270916 -0.16991 0.0356236 -0.0270916 -0.171816 0.0248504 -0.0270916 -0.167975 0.0296538 -0.0301473 -0.169478 0.0192936 -0.0301473 -0.169973 0.0142886 -0.0301473 -0.17354 0.00472304 -0.0270916 -0.17334 0.00957087 -0.0270916 -0.149356 0 -0.0402051 -0.149162 -0.00405959 -0.0402139 -0.152399 0 -0.0398278 -0.170313 -0.00940375 -0.0301473 -0.156595 -0.00426189 -0.0387046 -0.15538 0 -0.0391121 -0.152883 -0.00416085 -0.039724 -0.167975 -0.0296538 -0.0301473 -0.16139 -0.0284914 -0.0352405 -0.157875 -0.0278708 -0.0371966 -0.160398 -0.0336295 -0.0352405 -0.160634 -0.0573743 -0.0301473 -0.149867 -0.0663217 -0.0352405 -0.15031 -0.073501 -0.0328772 -0.153006 -0.067711 -0.0328772 -0.153233 -0.0749303 -0.0301473 -0.129501 -0.100439 -0.0352405 -0.127602 -0.108228 -0.0328772 -0.132214 -0.102543 -0.0328772 -0.111673 -0.124598 -0.0328772 -0.0972711 -0.131898 -0.0352405 -0.0993087 -0.13466 -0.0328772 -0.0856002 -0.143765 -0.0328772 -0.0782715 -0.147882 -0.0328772 -0.0614661 -0.151923 -0.0352405 -0.0546099 -0.158156 -0.0328772 -0.0627537 -0.155105 -0.0328772 -0.0534895 -0.154911 -0.0352405 -0.028976 -0.164791 -0.0328772 -0.0201396 -0.166103 -0.0328772 -0.0112168 -0.166943 -0.0328772 -0.00224579 -0.167304 -0.0328772 0.00673495 -0.167183 -0.0328772 0.0156866 -0.166582 -0.0328772 0.0326661 -0.160597 -0.0352405 0.0333504 -0.163962 -0.0328772 0.0504533 -0.159531 -0.0328772 0.0587112 -0.15668 -0.0328772 0.066734 -0.153435 -0.0328772 0.0802918 -0.14287 -0.0352405 0.0891487 -0.141592 -0.0328772 0.0819738 -0.145863 -0.0328772 0.0960045 -0.137036 -0.0328772 0.11757 -0.114175 -0.0352405 0.125166 -0.111036 -0.0328772 0.120032 -0.116567 -0.0328772 0.134392 -0.0996722 -0.0328772 0.148854 -0.0764084 -0.0328772 0.145714 -0.0822375 -0.0328772 0.142724 -0.0805502 -0.0352405 0.151748 -0.0778942 -0.0301473 0.155295 -0.0523656 -0.0352405 0.153317 -0.0579021 -0.0352405 0.149977 -0.0566409 -0.0371966 0.159572 -0.0602645 -0.0301473 0.161631 -0.0545021 -0.0301473 0.163438 -0.0488169 -0.0301473 0.165007 -0.0432185 -0.0301473 0.166351 -0.0377153 -0.0301473 0.167484 -0.0323142 -0.0301473 0.168419 -0.027021 -0.0301473 0.169169 -0.0218405 -0.0301473 0.169746 -0.0167762 -0.0301473 0.170162 -0.0118311 -0.0301473 0.170429 -0.00700687 -0.0301473 0.170557 -0.00230493 -0.0301473 0.170557 0.00230493 -0.0301473 0.170429 0.00700687 -0.0301473 0.170162 0.0118311 -0.0301473 0.169746 0.0167762 -0.0301473 0.169169 0.0218405 -0.0301473 0.168419 0.027021 -0.0301473 0.167484 0.0323142 -0.0301473 0.163438 0.0488169 -0.0301473 0.153317 0.0579021 -0.0352405 0.154248 0.0648321 -0.0328772 0.156528 0.059115 -0.0328772 0.157247 0.0660928 -0.0301473 0.151694 0.0706013 -0.0328772 0.145714 0.0822375 -0.0328772 0.138493 0.0938897 -0.0328772 0.129951 0.105396 -0.0328772 0.11757 0.114175 -0.0352405 0.114547 0.121961 -0.0328772 0.120032 0.116567 -0.0328772 0.108712 0.127191 -0.0328772 0.0891487 0.141592 -0.0328772 0.0819738 0.145863 -0.0328772 0.0744957 0.14982 -0.0328772 0.0575066 0.153465 -0.0352405 0.0504533 0.159531 -0.0328772 0.0587112 0.15668 -0.0328772 0.0494182 0.156258 -0.0352405 0.0333504 0.163962 -0.0328772 0.0245709 0.165505 -0.0328772 0.0156866 0.166582 -0.0328772 0.00673495 0.167183 -0.0328772 -0.00224579 0.167304 -0.0328772 -0.0112168 0.166943 -0.0328772 -0.0283815 0.16141 -0.0352405 -0.0376896 0.163019 -0.0328772 -0.028976 0.164791 -0.0328772 -0.0369163 0.159674 -0.0352405 -0.0546099 0.158156 -0.0328772 -0.0627537 0.155105 -0.0328772 -0.0766656 0.144848 -0.0352405 -0.0782715 0.147882 -0.0328772 -0.0926173 0.139347 -0.0328772 -0.103495 0.127072 -0.0352405 -0.111673 0.124598 -0.0328772 -0.105663 0.129734 -0.0328772 -0.147226 0.071993 -0.0352405 -0.153006 0.067711 -0.0328772 -0.15031 0.073501 -0.0328772 -0.155981 0.0690277 -0.0301473 -0.165706 0.0404546 -0.0301473 -0.168816 0.0244164 -0.0301473 -0.164771 0.0290882 -0.0328772 -0.166943 0.0350016 -0.0301473 -0.166245 0.0189256 -0.0328772 -0.166731 0.0140161 -0.0328772 -0.170509 0.00464057 -0.0301473 -0.170313 0.00940375 -0.0301473 -0.166295 0 -0.0336341 -0.167065 -0.00922437 -0.0328772 -0.166731 -0.0140161 -0.0328772 -0.152402 -0.0128115 -0.039724 -0.151958 -0.0172991 -0.039724 -0.155648 -0.0177192 -0.0387046 -0.164771 -0.0290882 -0.0328772 -0.163758 -0.034334 -0.0328772 -0.155421 -0.0619662 -0.0328772 -0.144299 -0.0776938 -0.0352405 -0.144029 -0.0851549 -0.0328772 -0.137538 -0.0891168 -0.0352405 -0.136484 -0.0967869 -0.0328772 -0.11751 -0.109054 -0.0371966 -0.114926 -0.116836 -0.0352405 -0.120127 -0.111482 -0.0352405 -0.122643 -0.113817 -0.0328772 -0.101241 -0.124305 -0.0371966 -0.103495 -0.127072 -0.0352405 -0.105663 -0.129734 -0.0328772 -0.090717 -0.136488 -0.0352405 -0.0838439 -0.140815 -0.0352405 -0.0676922 -0.145324 -0.0371966 -0.0691994 -0.14856 -0.0352405 -0.070649 -0.151672 -0.0328772 -0.0452963 -0.157502 -0.0352405 -0.0369163 -0.159674 -0.0352405 -0.0283815 -0.16141 -0.0352405 -0.0197263 -0.162694 -0.0352405 -0.0109867 -0.163517 -0.0352405 0.00645308 -0.160187 -0.0371966 0.0153648 -0.163164 -0.0352405 0.00659676 -0.163753 -0.0352405 0.0150301 -0.15961 -0.0371966 0.0240668 -0.162109 -0.0352405 0.0235426 -0.158578 -0.0371966 0.0245709 -0.165505 -0.0328772 0.0411277 -0.158642 -0.0352405 0.0494182 -0.156258 -0.0352405 0.0575066 -0.153465 -0.0352405 0.071378 -0.14355 -0.0371966 0.0729673 -0.146746 -0.0352405 0.0744957 -0.14982 -0.0328772 0.0873196 -0.138686 -0.0352405 0.0982376 -0.126692 -0.0371966 0.106481 -0.124581 -0.0352405 0.100425 -0.129512 -0.0352405 0.102529 -0.132225 -0.0328772 0.114547 -0.121961 -0.0328772 0.124513 -0.100985 -0.0371966 0.131634 -0.0976272 -0.0352405 0.127285 -0.103233 -0.0352405 0.129951 -0.105396 -0.0328772 0.132697 -0.0899603 -0.0371966 0.139345 -0.0862641 -0.0352405 0.135652 -0.0919633 -0.0352405 0.138493 -0.0938897 -0.0328772 0.142264 -0.0880711 -0.0328772 0.151694 -0.0706013 -0.0328772 0.154248 -0.0648321 -0.0328772 0.156528 -0.059115 -0.0328772 0.158548 -0.0534625 -0.0328772 0.16032 -0.0478857 -0.0328772 0.161859 -0.0423942 -0.0328772 0.163178 -0.0369959 -0.0328772 0.165942 -0.0214239 -0.0328772 0.166508 -0.0164563 -0.0328772 0.166916 -0.0116054 -0.0328772 0.167178 -0.00687322 -0.0328772 0.167304 -0.00226096 -0.0328772 0.167304 0.00226096 -0.0328772 0.167178 0.00687322 -0.0328772 0.166916 0.0116054 -0.0328772 0.166508 0.0164563 -0.0328772 0.165942 0.0214239 -0.0328772 0.165206 0.0265056 -0.0328772 0.164289 0.0316978 -0.0328772 0.155085 0.0406199 -0.0371966 0.157031 0.0469032 -0.0352405 0.158538 0.0415243 -0.0352405 0.161859 0.0423942 -0.0328772 0.16032 0.0478857 -0.0328772 0.158548 0.0534625 -0.0328772 0.142624 0.0732106 -0.0371966 0.142724 0.0805502 -0.0352405 0.1458 0.0748407 -0.0352405 0.148854 0.0764084 -0.0328772 0.13631 0.0843852 -0.0371966 0.135652 0.0919633 -0.0352405 0.139345 0.0862641 -0.0352405 0.142264 0.0880711 -0.0328772 0.128767 0.0955008 -0.0371966 0.127285 0.103233 -0.0352405 0.131634 0.0976272 -0.0352405 0.134392 0.0996722 -0.0328772 0.125166 0.111036 -0.0328772 0.112197 0.119459 -0.0352405 0.0982376 0.126692 -0.0371966 0.0940347 0.134224 -0.0352405 0.100425 0.129512 -0.0352405 0.102529 0.132225 -0.0328772 0.0873196 0.138686 -0.0352405 0.0802918 0.14287 -0.0352405 0.0639411 0.147013 -0.0371966 0.0653648 0.150287 -0.0352405 0.066734 0.153435 -0.0328772 0.0411277 0.158642 -0.0352405 0.0326661 0.160597 -0.0352405 0.0240668 0.162109 -0.0352405 0.0153648 0.163164 -0.0352405 0.00659676 0.163753 -0.0352405 -0.0107474 0.159956 -0.0371966 -0.0197263 0.162694 -0.0352405 -0.0109867 0.163517 -0.0352405 -0.0192967 0.159151 -0.0371966 -0.0201396 0.166103 -0.0328772 -0.0452963 0.157502 -0.0352405 -0.0534895 0.154911 -0.0352405 -0.0676922 0.145324 -0.0371966 -0.0691994 0.14856 -0.0352405 -0.070649 0.151672 -0.0328772 -0.0838439 0.140815 -0.0352405 -0.0951525 0.129025 -0.0371966 -0.0972711 0.131898 -0.0352405 -0.0993087 0.13466 -0.0328772 -0.112423 0.114291 -0.0371966 -0.120127 0.111482 -0.0352405 -0.114926 0.116836 -0.0352405 -0.117334 0.119283 -0.0328772 -0.127602 0.108228 -0.0328772 -0.129501 0.100439 -0.0352405 -0.136484 0.0967869 -0.0328772 -0.138001 0.0815911 -0.0371966 -0.144299 0.0776938 -0.0352405 -0.141074 0.0834078 -0.0352405 -0.150975 0.0539245 -0.0371966 -0.162545 0.0396829 -0.0328772 -0.163758 0.034334 -0.0328772 -0.165596 0.0239507 -0.0328772 -0.16139 0.0284914 -0.0352405 -0.162834 0.0185373 -0.0352405 -0.16331 0.0137285 -0.0352405 -0.167257 0.00455206 -0.0328772 -0.167065 0.00922437 -0.0328772 -0.160257 -0.00436155 -0.0371966 -0.163637 -0.00903511 -0.0352405 -0.16331 -0.0137285 -0.0352405 -0.162834 -0.0185373 -0.0352405 -0.162198 -0.0234593 -0.0352405 -0.147526 -0.0526924 -0.0387046 -0.148917 -0.0593728 -0.0371966 -0.150975 -0.0539245 -0.0371966 -0.154337 -0.0551252 -0.0352405 -0.152233 -0.0606948 -0.0352405 -0.146603 -0.0648772 -0.0371966 -0.147226 -0.071993 -0.0352405 -0.134543 -0.0871758 -0.0371966 -0.138001 -0.0815911 -0.0371966 -0.134848 -0.0797268 -0.0387046 -0.141074 -0.0834078 -0.0352405 -0.126681 -0.0982514 -0.0371966 -0.130772 -0.0927362 -0.0371966 -0.127784 -0.0906172 -0.0387046 -0.133684 -0.094801 -0.0352405 -0.124984 -0.106007 -0.0352405 -0.109382 -0.122042 -0.0352405 -0.112423 -0.114291 -0.0371966 -0.0951525 -0.129025 -0.0371966 -0.0887412 -0.133515 -0.0371966 -0.0749957 -0.141693 -0.0371966 -0.0732821 -0.138456 -0.0387046 -0.0766656 -0.144848 -0.0352405 -0.0601274 -0.148614 -0.0371966 -0.0523244 -0.151537 -0.0371966 -0.0443097 -0.154072 -0.0371966 -0.0361122 -0.156196 -0.0371966 -0.0277633 -0.157894 -0.0371966 -0.0021518 -0.160302 -0.0371966 -0.0107474 -0.159956 -0.0371966 -0.0105018 -0.156301 -0.0387046 -0.00210263 -0.156639 -0.0387046 -0.00219971 -0.163871 -0.0352405 0.0319546 -0.1571 -0.0371966 0.0402319 -0.155186 -0.0371966 0.0483418 -0.152854 -0.0371966 0.0639411 -0.147013 -0.0371966 0.0624801 -0.143654 -0.0387046 0.0653648 -0.150287 -0.0352405 0.0785431 -0.139758 -0.0371966 0.0919866 -0.131301 -0.0371966 0.0898847 -0.1283 -0.0387046 0.0940347 -0.134224 -0.0352405 0.115009 -0.111689 -0.0371966 0.109753 -0.116857 -0.0371966 0.107245 -0.114187 -0.0387046 0.112197 -0.119459 -0.0352405 0.122598 -0.108758 -0.0352405 0.139365 -0.0715378 -0.0387046 0.145346 -0.0676465 -0.0371966 0.142624 -0.0732106 -0.0371966 0.1458 -0.0748407 -0.0352405 0.148582 -0.0691527 -0.0352405 0.151083 -0.0635019 -0.0352405 0.157031 -0.0469032 -0.0352405 0.158538 -0.0415243 -0.0352405 0.15983 -0.0362368 -0.0352405 0.158997 -0.0205273 -0.0371966 0.163091 -0.0161186 -0.0352405 0.162537 -0.0209843 -0.0352405 0.161817 -0.0259618 -0.0352405 0.163491 -0.0113673 -0.0352405 0.163748 -0.0067322 -0.0352405 0.163871 -0.00221457 -0.0352405 0.163871 0.00221457 -0.0352405 0.163748 0.0067322 -0.0352405 0.163491 0.0113673 -0.0352405 0.163091 0.0161186 -0.0352405 0.162537 0.0209843 -0.0352405 0.161817 0.0259618 -0.0352405 0.160918 0.0310475 -0.0352405 0.15983 0.0362368 -0.0352405 0.155295 0.0523656 -0.0352405 0.144416 0.0606994 -0.0387046 0.145346 0.0676465 -0.0371966 0.147793 0.0621188 -0.0371966 0.151083 0.0635019 -0.0352405 0.148582 0.0691527 -0.0352405 0.115009 0.111689 -0.0371966 0.119928 0.106389 -0.0371966 0.117188 0.103958 -0.0387046 0.122598 0.108758 -0.0352405 0.104162 0.121867 -0.0371966 0.101782 0.119083 -0.0387046 0.106481 0.124581 -0.0352405 0.0919866 0.131301 -0.0371966 0.071378 0.14355 -0.0371966 0.0785431 0.139758 -0.0371966 0.0767484 0.136565 -0.0387046 0.069747 0.14027 -0.0387046 0.0729673 0.146746 -0.0352405 0.0562541 0.150123 -0.0371966 0.0483418 0.152854 -0.0371966 0.0402319 0.155186 -0.0371966 0.0319546 0.1571 -0.0371966 0.00645308 0.160187 -0.0371966 0.0150301 0.15961 -0.0371966 0.0146867 0.155963 -0.0387046 -0.0021518 0.160302 -0.0371966 0.00630563 0.156526 -0.0387046 -0.00210263 0.156639 -0.0387046 -0.00219971 0.163871 -0.0352405 -0.0277633 0.157894 -0.0371966 -0.0361122 0.156196 -0.0371966 -0.0443097 0.154072 -0.0371966 -0.0601274 0.148614 -0.0371966 -0.0587535 0.145218 -0.0387046 -0.0614661 0.151923 -0.0352405 -0.0749957 0.141693 -0.0371966 -0.090717 0.136488 -0.0352405 -0.0820177 0.137748 -0.0371966 -0.101241 0.124305 -0.0371966 -0.109382 0.122042 -0.0352405 -0.126681 0.0982514 -0.0371966 -0.122262 0.103699 -0.0371966 -0.119468 0.101329 -0.0387046 -0.124984 0.106007 -0.0352405 -0.134543 0.0871758 -0.0371966 -0.130772 0.0927362 -0.0371966 -0.127784 0.0906172 -0.0387046 -0.133684 0.094801 -0.0352405 -0.137538 0.0891168 -0.0352405 -0.143253 0.0633948 -0.0387046 -0.148917 0.0593728 -0.0371966 -0.146603 0.0648772 -0.0371966 -0.149867 0.0663217 -0.0352405 -0.152233 0.0606948 -0.0352405 -0.15921 0.0388687 -0.0352405 -0.160398 0.0336295 -0.0352405 -0.162198 0.0234593 -0.0352405 -0.157875 0.0278708 -0.0371966 -0.163637 0.00903511 -0.0352405 -0.163825 0.00445866 -0.0352405 -0.158274 0 -0.0380982 -0.160073 -0.00883832 -0.0371966 -0.159753 -0.0134295 -0.0371966 -0.159288 -0.0181336 -0.0371966 -0.158666 -0.0229483 -0.0371966 -0.151364 -0.0218924 -0.039724 -0.14826 -0.0168781 -0.0402139 -0.147681 -0.0213596 -0.0402139 -0.15061 -0.0265883 -0.039724 -0.154375 -0.0432401 -0.0371966 -0.15279 -0.0485437 -0.0371966 -0.137393 -0.0671843 -0.039724 -0.137931 -0.074265 -0.0387046 -0.140729 -0.0688158 -0.0387046 -0.14402 -0.0704249 -0.0371966 -0.141156 -0.0760016 -0.0371966 -0.116636 -0.0989267 -0.039724 -0.114825 -0.106562 -0.0387046 -0.119468 -0.101329 -0.0387046 -0.122262 -0.103699 -0.0371966 -0.0989277 -0.121464 -0.0387046 -0.104555 -0.116656 -0.0387046 -0.102076 -0.11389 -0.039724 -0.106999 -0.119384 -0.0371966 -0.0929783 -0.126077 -0.0387046 -0.0801436 -0.1346 -0.0387046 -0.0782436 -0.131409 -0.039724 -0.0820177 -0.137748 -0.0371966 -0.0661455 -0.142004 -0.0387046 -0.0587535 -0.145218 -0.0387046 -0.0511289 -0.148075 -0.0387046 -0.027129 -0.154286 -0.0387046 -0.0352871 -0.152627 -0.0387046 -0.0344505 -0.149009 -0.039724 -0.0188558 -0.155514 -0.0387046 -0.0264858 -0.150629 -0.039724 -0.0184087 -0.151827 -0.039724 -0.0192967 -0.159151 -0.0371966 0.00630563 -0.156526 -0.0387046 0.0146867 -0.155963 -0.0387046 0.0230046 -0.154955 -0.0387046 0.0312245 -0.15351 -0.0387046 0.0549687 -0.146693 -0.0387046 0.0472372 -0.149362 -0.0387046 0.0461173 -0.145821 -0.039724 0.0536655 -0.143215 -0.039724 0.0562541 -0.150123 -0.0371966 0.069747 -0.14027 -0.0387046 0.0767484 -0.136565 -0.0387046 0.0854177 -0.135666 -0.0371966 0.095993 -0.123797 -0.0387046 0.104162 -0.121867 -0.0371966 0.114409 -0.101494 -0.039724 0.121668 -0.0986774 -0.0387046 0.117188 -0.103958 -0.0387046 0.119928 -0.106389 -0.0371966 0.128767 -0.0955008 -0.0371966 0.130038 -0.0805022 -0.039724 0.136426 -0.0769953 -0.0387046 0.133196 -0.0824571 -0.0387046 0.13631 -0.0843852 -0.0371966 0.139616 -0.0787958 -0.0371966 0.147793 -0.0621188 -0.0371966 0.144922 -0.0488679 -0.039724 0.150101 -0.0448333 -0.0387046 0.148441 -0.0500546 -0.0387046 0.151912 -0.051225 -0.0371966 0.153611 -0.0458817 -0.0371966 0.155085 -0.0406199 -0.0371966 0.156348 -0.0354476 -0.0371966 0.157413 -0.0303712 -0.0371966 0.158292 -0.0253963 -0.0371966 0.159539 -0.0157675 -0.0371966 0.15993 -0.0111197 -0.0371966 0.160181 -0.00658557 -0.0371966 0.160302 -0.00216634 -0.0371966 0.160302 0.00216634 -0.0371966 0.160181 0.00658557 -0.0371966 0.155894 0.0154073 -0.0387046 0.158997 0.0205273 -0.0371966 0.159539 0.0157675 -0.0371966 0.15993 0.0111197 -0.0371966 0.158292 0.0253963 -0.0371966 0.157413 0.0303712 -0.0371966 0.156348 0.0354476 -0.0371966 0.146542 0.0437704 -0.039724 0.148441 0.0500546 -0.0387046 0.150101 0.0448333 -0.0387046 0.153611 0.0458817 -0.0371966 0.151912 0.051225 -0.0371966 0.149977 0.0566409 -0.0371966 0.139365 0.0715378 -0.0387046 0.139616 0.0787958 -0.0371966 0.133196 0.0824571 -0.0387046 0.132697 0.0899603 -0.0371966 0.125825 0.0933187 -0.0387046 0.124513 0.100985 -0.0371966 0.112381 0.109137 -0.0387046 0.109753 0.116857 -0.0371966 0.095993 0.123797 -0.0387046 0.0814871 0.129423 -0.039724 0.0834659 0.132566 -0.0387046 0.0854177 0.135666 -0.0371966 0.0624801 0.143654 -0.0387046 0.0549687 0.146693 -0.0387046 0.0472372 0.149362 -0.0387046 0.0230046 0.154955 -0.0387046 0.0312245 0.15351 -0.0387046 0.0304842 0.14987 -0.039724 0.0224592 0.151281 -0.039724 0.0235426 0.158578 -0.0371966 -0.0105018 0.156301 -0.0387046 -0.0188558 0.155514 -0.0387046 -0.027129 0.154286 -0.0387046 -0.0352871 0.152627 -0.0387046 -0.0511289 0.148075 -0.0387046 -0.0499167 0.144564 -0.039724 -0.0523244 0.151537 -0.0371966 -0.0661455 0.142004 -0.0387046 -0.0732821 0.138456 -0.0387046 -0.0929783 0.126077 -0.0387046 -0.0867135 0.130465 -0.0387046 -0.0846577 0.127372 -0.039724 -0.0887412 0.133515 -0.0371966 -0.102076 0.11389 -0.039724 -0.109854 0.111679 -0.0387046 -0.104555 0.116656 -0.0387046 -0.106999 0.119384 -0.0371966 -0.11751 0.109054 -0.0371966 -0.134848 0.0797268 -0.0387046 -0.141156 0.0760016 -0.0371966 -0.14402 0.0704249 -0.0371966 -0.152184 0.0371533 -0.0387046 -0.150848 0.0422521 -0.0387046 -0.155742 0.0380221 -0.0371966 -0.147526 0.0526924 -0.0387046 -0.156905 0.032897 -0.0371966 -0.158666 0.0229483 -0.0371966 -0.159288 0.0181336 -0.0371966 -0.159753 0.0134295 -0.0371966 -0.155648 0.0177192 -0.0387046 -0.156103 0.0131226 -0.0387046 -0.160257 0.00436155 -0.0371966 -0.160073 0.00883832 -0.0371966 -0.131993 0 -0.0351034 -0.134875 -0.00367074 -0.0368012 -0.13464 0 -0.0366517 -0.156415 -0.00863637 -0.0387046 -0.156103 -0.0131226 -0.0387046 -0.15504 -0.022424 -0.0387046 -0.154268 -0.027234 -0.0387046 -0.150848 -0.0422521 -0.0387046 -0.149299 -0.0474345 -0.0387046 -0.138607 -0.0552623 -0.0402139 -0.139857 -0.0618918 -0.039724 -0.142064 -0.0566407 -0.039724 -0.145514 -0.0580162 -0.0387046 -0.143253 -0.0633948 -0.0387046 -0.131651 -0.0778366 -0.039724 -0.131469 -0.0851839 -0.0387046 -0.124755 -0.0884689 -0.039724 -0.123786 -0.0960064 -0.0387046 -0.10725 -0.109032 -0.039724 -0.10464 -0.106378 -0.0402139 -0.109854 -0.111679 -0.0387046 -0.0965824 -0.118585 -0.039724 -0.0825975 -0.124272 -0.0402139 -0.0846577 -0.127372 -0.039724 -0.0867135 -0.130465 -0.0387046 -0.0715447 -0.135173 -0.039724 -0.0645773 -0.138637 -0.039724 -0.0573606 -0.141775 -0.039724 -0.0422708 -0.146982 -0.039724 -0.0412421 -0.143405 -0.0402139 -0.0432973 -0.150551 -0.0387046 -0.0102528 -0.152595 -0.039724 -0.00205279 -0.152926 -0.039724 0.00615614 -0.152815 -0.039724 0.0143385 -0.152266 -0.039724 0.0224592 -0.151281 -0.039724 0.0383806 -0.148045 -0.039724 0.0374466 -0.144442 -0.0402139 0.0393126 -0.15164 -0.0387046 0.0609988 -0.140248 -0.039724 0.0680935 -0.136944 -0.039724 0.0795041 -0.126273 -0.0402139 0.0877537 -0.125259 -0.039724 0.0814871 -0.129423 -0.039724 0.0834659 -0.132566 -0.0387046 0.0969506 -0.11343 -0.0402139 0.104703 -0.11148 -0.039724 0.0993688 -0.11626 -0.039724 0.101782 -0.119083 -0.0387046 0.112381 -0.109137 -0.0387046 0.119852 -0.0888891 -0.0402139 0.126591 -0.0858207 -0.039724 0.122842 -0.0911063 -0.039724 0.125825 -0.0933187 -0.0387046 0.129665 -0.0879048 -0.0387046 0.135283 -0.0629632 -0.0402139 0.140992 -0.0592603 -0.039724 0.138657 -0.0645337 -0.039724 0.142024 -0.0661008 -0.0387046 0.144416 -0.0606994 -0.0387046 0.14655 -0.0553467 -0.0387046 0.151542 -0.0396918 -0.0387046 0.152776 -0.0346376 -0.0387046 0.153817 -0.0296773 -0.0387046 0.154675 -0.024816 -0.0387046 0.155364 -0.0200582 -0.0387046 0.155894 -0.0154073 -0.0387046 0.156276 -0.0108656 -0.0387046 0.156521 -0.00643509 -0.0387046 0.156639 -0.00211684 -0.0387046 0.156639 0.00211684 -0.0387046 0.156521 0.00643509 -0.0387046 0.156276 0.0108656 -0.0387046 0.146515 0.0282686 -0.0402139 0.142895 0.02757 -0.0401362 0.145524 0.0329935 -0.0402139 0.155364 0.0200582 -0.0387046 0.154675 0.024816 -0.0387046 0.153817 0.0296773 -0.0387046 0.152776 0.0346376 -0.0387046 0.151542 0.0396918 -0.0387046 0.14655 0.0553467 -0.0387046 0.140992 0.0592603 -0.039724 0.142024 0.0661008 -0.0387046 0.12995 0.0733406 -0.0402139 0.130038 0.0805022 -0.039724 0.133191 0.0751699 -0.039724 0.136426 0.0769953 -0.0387046 0.12351 0.0837322 -0.0402139 0.122842 0.0911063 -0.039724 0.126591 0.0858207 -0.039724 0.129665 0.0879048 -0.0387046 0.115893 0.0939936 -0.0402139 0.114409 0.101494 -0.039724 0.118783 0.096338 -0.039724 0.121668 0.0986774 -0.0387046 0.102155 0.108767 -0.0402139 0.0993688 0.11626 -0.039724 0.104703 0.11148 -0.039724 0.107245 0.114187 -0.0387046 0.0877537 0.125259 -0.039724 0.0856182 0.12221 -0.0402139 0.0898847 0.1283 -0.0387046 0.0749288 0.133327 -0.039724 0.0680935 0.136944 -0.039724 0.0609988 0.140248 -0.039724 0.0461173 0.145821 -0.039724 0.044995 0.142272 -0.0402139 0.0383806 0.148045 -0.039724 0.0374466 0.144442 -0.0402139 0.0393126 0.15164 -0.0387046 0.0143385 0.152266 -0.039724 0.00615614 0.152815 -0.039724 -0.00205279 0.152926 -0.039724 -0.0102528 0.152595 -0.039724 -0.0184087 0.151827 -0.039724 -0.0344505 0.149009 -0.039724 -0.0336121 0.145383 -0.0402139 -0.0422708 0.146982 -0.039724 -0.0412421 0.143405 -0.0402139 -0.0432973 0.150551 -0.0387046 -0.0573606 0.141775 -0.039724 -0.0645773 0.138637 -0.039724 -0.0782436 0.131409 -0.039724 -0.0763395 0.128211 -0.0402139 -0.0801436 0.1346 -0.0387046 -0.090774 0.123088 -0.039724 -0.0989277 0.121464 -0.0387046 -0.109375 0.101504 -0.0402139 -0.116636 0.0989267 -0.039724 -0.112103 0.104035 -0.039724 -0.114825 0.106562 -0.0387046 -0.123786 0.0960064 -0.0387046 -0.124755 0.0884689 -0.039724 -0.131469 0.0851839 -0.0387046 -0.131384 0.0707399 -0.0402139 -0.137393 0.0671843 -0.039724 -0.134661 0.0725043 -0.039724 -0.137931 0.074265 -0.0387046 -0.140729 0.0688158 -0.0387046 -0.138607 0.0552623 -0.0402139 -0.144028 0.0514432 -0.039724 -0.142064 0.0566407 -0.039724 -0.145514 0.0580162 -0.0387046 -0.14576 0.0463099 -0.039724 -0.154268 0.027234 -0.0387046 -0.15332 0.0321454 -0.0387046 -0.15504 0.022424 -0.0387046 -0.151958 0.0172991 -0.039724 -0.152402 0.0128115 -0.039724 -0.156595 0.00426189 -0.0387046 -0.156415 0.00863637 -0.0387046 -0.152707 -0.00843162 -0.039724 -0.138314 -0.00376435 -0.0383714 -0.137404 0 -0.0379798 -0.147271 -0.0412503 -0.039724 -0.14576 -0.0463099 -0.039724 -0.144028 -0.0514432 -0.039724 -0.131384 -0.0707399 -0.0402139 -0.128137 -0.0689917 -0.0401362 -0.128447 -0.0759424 -0.0402139 -0.134661 -0.0725043 -0.039724 -0.125228 -0.0811405 -0.0402139 -0.122133 -0.0791353 -0.0401362 -0.121719 -0.0863159 -0.0402139 -0.128352 -0.0831643 -0.039724 -0.117911 -0.0914492 -0.0402139 -0.114997 -0.0891893 -0.0401362 -0.113798 -0.0965193 -0.0402139 -0.120852 -0.0937302 -0.039724 -0.112103 -0.104035 -0.039724 -0.0995917 -0.111119 -0.0402139 -0.0885649 -0.120092 -0.0402139 -0.0863762 -0.117124 -0.0401362 -0.090774 -0.123088 -0.039724 -0.0763395 -0.128211 -0.0402139 -0.0698037 -0.131884 -0.0402139 -0.0559647 -0.138325 -0.0402139 -0.0545816 -0.134907 -0.0401362 -0.0487019 -0.141046 -0.0402139 -0.0474984 -0.13756 -0.0401362 -0.0499167 -0.144564 -0.039724 -0.0336121 -0.145383 -0.0402139 -0.0258412 -0.146963 -0.0402139 -0.0179607 -0.148133 -0.0402139 -0.0100033 -0.148882 -0.0402139 -0.00200283 -0.149204 -0.0402139 0.00600632 -0.149097 -0.0402139 0.0219127 -0.1476 -0.0402139 0.0213712 -0.143952 -0.0401362 0.0297424 -0.146223 -0.0402139 0.0290073 -0.14261 -0.0401362 0.0304842 -0.14987 -0.039724 0.044995 -0.142272 -0.0402139 0.0523595 -0.13973 -0.0402139 0.0595143 -0.136835 -0.0402139 0.0731054 -0.130083 -0.0402139 0.0712987 -0.126868 -0.0401362 0.0749288 -0.133327 -0.039724 0.0856182 -0.12221 -0.0402139 0.0937172 -0.120862 -0.039724 0.102155 -0.108767 -0.0402139 0.109717 -0.106549 -0.039724 0.111625 -0.0990236 -0.0402139 0.118783 -0.096338 -0.039724 0.126873 -0.0785431 -0.0402139 0.133191 -0.0751699 -0.039724 0.136061 -0.0698417 -0.039724 0.143076 -0.0540345 -0.039724 0.133221 -0.0213739 -0.0368012 0.136618 -0.021919 -0.0383714 0.132481 -0.0255609 -0.0368012 0.146542 -0.0437704 -0.039724 0.147949 -0.0387507 -0.039724 0.149154 -0.0338164 -0.039724 0.15017 -0.0289737 -0.039724 0.151008 -0.0242277 -0.039724 0.15168 -0.0195827 -0.039724 0.152198 -0.015042 -0.039724 0.152571 -0.010608 -0.039724 0.15281 -0.00628253 -0.039724 0.152925 -0.00206665 -0.039724 0.152925 0.00206665 -0.039724 0.15281 0.00628253 -0.039724 0.152571 0.010608 -0.039724 0.152198 0.015042 -0.039724 0.15168 0.0195827 -0.039724 0.151008 0.0242277 -0.039724 0.15017 0.0289737 -0.039724 0.149154 0.0338164 -0.039724 0.147949 0.0387507 -0.039724 0.137901 0.0465004 -0.0401362 0.139594 0.0527196 -0.0402139 0.141395 0.0476786 -0.0402139 0.144922 0.0488679 -0.039724 0.143076 0.0540345 -0.039724 0.13194 0.0614072 -0.0401362 0.13275 0.0681421 -0.0402139 0.135283 0.0629632 -0.0402139 0.138657 0.0645337 -0.039724 0.136061 0.0698417 -0.039724 0.107047 0.103956 -0.0402139 0.104401 0.101387 -0.0401362 0.109717 0.106549 -0.039724 0.0969506 0.11343 -0.0402139 0.0937172 0.120862 -0.039724 0.0795041 0.126273 -0.0402139 0.0731054 0.130083 -0.0402139 0.0595143 0.136835 -0.0402139 0.0580436 0.133454 -0.0401362 0.0523595 0.13973 -0.0402139 0.0510656 0.136276 -0.0401362 0.0536655 0.143215 -0.039724 0.0297424 0.146223 -0.0402139 0.0219127 0.1476 -0.0402139 0.0139896 0.14856 -0.0402139 0.00600632 0.149097 -0.0402139 -0.00200283 0.149204 -0.0402139 -0.0179607 0.148133 -0.0402139 -0.0175169 0.144472 -0.0401362 -0.0258412 0.146963 -0.0402139 -0.0252026 0.143331 -0.0401362 -0.0264858 0.150629 -0.039724 -0.0487019 0.141046 -0.0402139 -0.0559647 0.138325 -0.0402139 -0.0698037 0.131884 -0.0402139 -0.0680786 0.128624 -0.0401362 -0.0715447 0.135173 -0.039724 -0.0825975 0.124272 -0.0402139 -0.094232 0.115699 -0.0402139 -0.0919032 0.11284 -0.0401362 -0.0995917 0.111119 -0.0402139 -0.0965824 0.118585 -0.039724 -0.10725 0.109032 -0.039724 -0.117911 0.0914492 -0.0402139 -0.114997 0.0891893 -0.0401362 -0.121719 0.0863159 -0.0402139 -0.120852 0.0937302 -0.039724 -0.122133 0.0791353 -0.0401362 -0.128447 0.0759424 -0.0402139 -0.125228 0.0811405 -0.0402139 -0.128352 0.0831643 -0.039724 -0.131651 0.0778366 -0.039724 -0.139857 0.0618918 -0.039724 -0.151364 0.0218924 -0.039724 -0.14826 0.0168781 -0.0402139 -0.148693 0.0124997 -0.0402139 -0.152883 0.00416085 -0.039724 -0.152707 0.00843162 -0.039724 -0.146291 0 -0.0402 -0.145476 -0.00395927 -0.0401362 -0.148991 -0.00822643 -0.0402139 -0.148693 -0.0124997 -0.0402139 -0.140996 -0.0160512 -0.0395028 -0.137879 -0.0115907 -0.0383714 -0.136258 -0.0240546 -0.0383714 -0.14496 -0.0353898 -0.0402139 -0.140523 -0.0501913 -0.0402139 -0.135182 -0.0538966 -0.0401362 -0.136453 -0.0603856 -0.0402139 -0.134049 -0.0655493 -0.0402139 -0.106672 -0.0989952 -0.0401362 -0.104016 -0.0965303 -0.0395028 -0.102054 -0.103749 -0.0401362 -0.109375 -0.101504 -0.0402139 -0.0919032 -0.11284 -0.0401362 -0.0896149 -0.11003 -0.0395028 -0.094232 -0.115699 -0.0402139 -0.0805563 -0.121201 -0.0401362 -0.0744529 -0.125043 -0.0401362 -0.0614487 -0.13192 -0.0401362 -0.0599187 -0.128636 -0.0395028 -0.0630058 -0.135263 -0.0402139 -0.0402229 -0.139861 -0.0401362 -0.0327814 -0.14179 -0.0401362 -0.0252026 -0.143331 -0.0401362 -0.0175169 -0.144472 -0.0401362 -0.00195333 -0.145517 -0.0401362 -0.0019047 -0.141894 -0.0395028 0.00585789 -0.145412 -0.0401362 0.00571204 -0.141791 -0.0395028 0.0136438 -0.144889 -0.0401362 0.0133041 -0.141281 -0.0395028 0.0139896 -0.14856 -0.0402139 0.0365212 -0.140873 -0.0401362 0.0438831 -0.138756 -0.0401362 0.0510656 -0.136276 -0.0401362 0.0647945 -0.13031 -0.0401362 0.0631812 -0.127065 -0.0395028 0.0664364 -0.133612 -0.0402139 0.0775393 -0.123153 -0.0401362 0.0891768 -0.115006 -0.0401362 0.0869564 -0.112143 -0.0395028 0.0945546 -0.110627 -0.0401362 0.0914365 -0.11792 -0.0402139 0.104401 -0.101387 -0.0401362 0.101802 -0.0988627 -0.0395028 0.108867 -0.0965765 -0.0401362 0.107047 -0.103956 -0.0402139 0.113028 -0.0916707 -0.0401362 0.110214 -0.0893882 -0.0395028 0.11689 -0.0866925 -0.0401362 0.115893 -0.0939936 -0.0402139 0.120458 -0.0816629 -0.0401362 0.117459 -0.0796296 -0.0395028 0.123738 -0.0766021 -0.0401362 0.12351 -0.0837322 -0.0402139 0.126739 -0.0715282 -0.0401362 0.123583 -0.0697472 -0.0395028 0.129469 -0.0664581 -0.0401362 0.12995 -0.0733406 -0.0402139 0.13275 -0.0681421 -0.0402139 0.134161 -0.0563893 -0.0401362 0.130821 -0.0549853 -0.0395028 0.136144 -0.0514167 -0.0401362 0.137561 -0.0578182 -0.0402139 0.139594 -0.0527196 -0.0402139 0.141395 -0.0476786 -0.0402139 0.142976 -0.0427052 -0.0402139 0.144348 -0.0378077 -0.0402139 0.145524 -0.0329935 -0.0402139 0.146515 -0.0282686 -0.0402139 0.147333 -0.0236381 -0.0402139 0.147989 -0.0191061 -0.0402139 0.148494 -0.0146759 -0.0402139 0.148858 -0.0103498 -0.0402139 0.149092 -0.00612964 -0.0402139 0.149204 -0.00201636 -0.0402139 0.149204 0.00201636 -0.0402139 0.149092 0.00612964 -0.0402139 0.148858 0.0103498 -0.0402139 0.148494 0.0146759 -0.0402139 0.147989 0.0191061 -0.0402139 0.147333 0.0236381 -0.0402139 0.144348 0.0378077 -0.0402139 0.142976 0.0427052 -0.0402139 0.137561 0.0578182 -0.0402139 0.123738 0.0766021 -0.0401362 0.120657 0.0746948 -0.0395028 0.120458 0.0816629 -0.0401362 0.126873 0.0785431 -0.0402139 0.119852 0.0888891 -0.0402139 0.113028 0.0916707 -0.0401362 0.111625 0.0990236 -0.0402139 0.0996304 0.106079 -0.0401362 0.0891768 0.115006 -0.0401362 0.0869564 0.112143 -0.0395028 0.0835023 0.11919 -0.0401362 0.0914365 0.11792 -0.0402139 0.0775393 0.123153 -0.0401362 0.0647945 0.13031 -0.0401362 0.0631812 0.127065 -0.0395028 0.0664364 0.133612 -0.0402139 0.0438831 0.138756 -0.0401362 0.0365212 0.140873 -0.0401362 0.0290073 0.14261 -0.0401362 0.0213712 0.143952 -0.0401362 0.0136438 0.144889 -0.0401362 -0.00195333 0.145517 -0.0401362 -0.0019047 0.141894 -0.0395028 -0.00975612 0.145203 -0.0401362 -0.00951321 0.141587 -0.0395028 -0.0100033 0.148882 -0.0402139 -0.0327814 0.14179 -0.0401362 -0.0402229 0.139861 -0.0401362 -0.0474984 0.13756 -0.0401362 -0.0614487 0.13192 -0.0401362 -0.0599187 0.128636 -0.0395028 -0.0630058 0.135263 -0.0402139 -0.0744529 0.125043 -0.0401362 -0.0805563 0.121201 -0.0401362 -0.0885649 0.120092 -0.0402139 -0.0971305 0.108373 -0.0401362 -0.10464 0.106378 -0.0402139 -0.106672 0.0989952 -0.0401362 -0.113798 0.0965193 -0.0402139 -0.130736 0.0639294 -0.0401362 -0.127481 0.0623376 -0.0395028 -0.133081 0.0588934 -0.0401362 -0.134049 0.0655493 -0.0402139 -0.136453 0.0603856 -0.0402139 -0.130303 0.046541 -0.0383714 -0.140523 0.0501913 -0.0402139 -0.142212 0.0451829 -0.0402139 -0.140445 0.0203131 -0.0395028 -0.13694 0.0198062 -0.0383714 -0.13705 0.0489509 -0.0401362 -0.138698 0.0440663 -0.0401362 -0.147681 0.0213596 -0.0402139 -0.143314 0.0253002 -0.0401362 -0.149162 0.00405959 -0.0402139 -0.148991 0.00822643 -0.0402139 -0.143251 0 -0.0398015 -0.141854 -0.00386068 -0.0395028 -0.145309 -0.00802313 -0.0401362 -0.145018 -0.0121908 -0.0401362 -0.144596 -0.016461 -0.0401362 -0.144031 -0.0208317 -0.0401362 -0.141378 -0.0345152 -0.0401362 -0.13187 -0.0418969 -0.0383714 -0.135245 -0.0429691 -0.0395028 -0.133237 -0.0373195 -0.0383714 -0.138698 -0.0440663 -0.0401362 -0.13705 -0.0489509 -0.0401362 -0.126529 -0.055994 -0.0383714 -0.129767 -0.057427 -0.0395028 -0.128527 -0.0512433 -0.0383714 -0.133081 -0.0588934 -0.0401362 -0.130736 -0.0639294 -0.0401362 -0.124947 -0.0672739 -0.0395028 -0.125273 -0.0740657 -0.0401362 -0.119092 -0.0771649 -0.0395028 -0.118711 -0.0841828 -0.0401362 -0.112133 -0.0869686 -0.0395028 -0.110985 -0.094134 -0.0401362 -0.099513 -0.101166 -0.0395028 -0.0971305 -0.108373 -0.0401362 -0.0842256 -0.114208 -0.0395028 -0.0785505 -0.118183 -0.0395028 -0.064727 -0.122292 -0.0383714 -0.0663835 -0.125422 -0.0395028 -0.0707875 -0.118887 -0.0383714 -0.0680786 -0.128624 -0.0401362 -0.0532226 -0.131548 -0.0395028 -0.0463157 -0.134135 -0.0395028 -0.0392214 -0.136379 -0.0395028 -0.0319652 -0.138259 -0.0395028 -0.0166545 -0.137359 -0.0383714 -0.0170807 -0.140875 -0.0395028 -0.0239619 -0.136275 -0.0383714 -0.00927582 -0.138054 -0.0383714 -0.00951321 -0.141587 -0.0395028 -0.00975612 -0.145203 -0.0401362 0.020839 -0.140368 -0.0395028 0.0282851 -0.139059 -0.0395028 0.0356118 -0.137365 -0.0395028 0.0485516 -0.129567 -0.0383714 0.0497941 -0.132883 -0.0395028 0.0417227 -0.131925 -0.0383714 0.055186 -0.126884 -0.0383714 0.0565984 -0.130131 -0.0395028 0.0580436 -0.133454 -0.0401362 0.0695235 -0.123709 -0.0395028 0.0793914 -0.113322 -0.0383714 0.0814232 -0.116223 -0.0395028 0.073722 -0.11709 -0.0383714 0.0835023 -0.11919 -0.0401362 0.0922003 -0.107873 -0.0395028 0.0996304 -0.106079 -0.0401362 0.13194 -0.0614072 -0.0401362 0.137901 -0.0465004 -0.0401362 0.139443 -0.0416498 -0.0401362 0.140781 -0.0368734 -0.0401362 0.141928 -0.0321781 -0.0401362 0.142895 -0.02757 -0.0401362 0.143692 -0.0230539 -0.0401362 0.144332 -0.018634 -0.0401362 0.144824 -0.0143132 -0.0401362 0.145179 -0.0100941 -0.0401362 0.145407 -0.00597816 -0.0401362 0.145517 -0.00196653 -0.0401362 0.145517 0.00196653 -0.0401362 0.145407 0.00597816 -0.0401362 0.145179 0.0100941 -0.0401362 0.144824 0.0143132 -0.0401362 0.144332 0.018634 -0.0401362 0.143692 0.0230539 -0.0401362 0.121685 0.0410323 -0.0325813 0.124704 0.0420502 -0.0348514 0.123045 0.0367521 -0.0325813 0.141928 0.0321781 -0.0401362 0.140781 0.0368734 -0.0401362 0.139443 0.0416498 -0.0401362 0.126223 0.0476698 -0.0368012 0.124384 0.0522801 -0.0368012 0.127556 0.0536132 -0.0383714 0.136144 0.0514167 -0.0401362 0.134161 0.0563893 -0.0401362 0.123095 0.0631863 -0.0383714 0.126246 0.0648034 -0.0395028 0.125444 0.0583841 -0.0383714 0.129469 0.0664581 -0.0401362 0.126739 0.0715282 -0.0401362 0.111136 0.0824245 -0.0383714 0.11398 0.0845339 -0.0395028 0.114528 0.0776426 -0.0383714 0.11689 0.0866925 -0.0401362 0.103507 0.0918219 -0.0383714 0.106156 0.0941718 -0.0395028 0.107464 0.0871577 -0.0383714 0.108867 0.0965765 -0.0401362 0.101802 0.0988627 -0.0395028 0.0898996 0.105181 -0.0383714 0.0922003 0.107873 -0.0395028 0.0947255 0.100857 -0.0383714 0.0945546 0.110627 -0.0401362 0.0814232 0.116223 -0.0395028 0.0677886 0.120622 -0.0383714 0.0695235 0.123709 -0.0395028 0.073722 0.11709 -0.0383714 0.0712987 0.126868 -0.0401362 0.0565984 0.130131 -0.0395028 0.0497941 0.132883 -0.0395028 0.0427904 0.135301 -0.0395028 0.0356118 0.137365 -0.0395028 0.020319 0.136865 -0.0383714 0.020839 0.140368 -0.0395028 0.0275793 0.135589 -0.0383714 0.0129721 0.137756 -0.0383714 0.0133041 0.141281 -0.0395028 0.0055695 0.138253 -0.0383714 0.00571204 0.141791 -0.0395028 0.00585789 0.145412 -0.0401362 -0.0170807 0.140875 -0.0395028 -0.0245751 0.139762 -0.0395028 -0.0319652 0.138259 -0.0395028 -0.0392214 0.136379 -0.0395028 -0.0518945 0.128265 -0.0383714 -0.0532226 0.131548 -0.0395028 -0.04516 0.130788 -0.0383714 -0.0545816 0.134907 -0.0401362 -0.0663835 0.125422 -0.0395028 -0.0725991 0.121929 -0.0395028 -0.0821238 0.111358 -0.0383714 -0.0842256 0.114208 -0.0395028 -0.0765904 0.115234 -0.0383714 -0.0863762 0.117124 -0.0401362 -0.0896149 0.11003 -0.0395028 -0.0970298 0.0986418 -0.0383714 -0.099513 0.101166 -0.0395028 -0.0923487 0.103037 -0.0383714 -0.102054 0.103749 -0.0401362 -0.104016 0.0965303 -0.0395028 -0.110985 0.094134 -0.0401362 -0.112133 0.0869686 -0.0395028 -0.118711 0.0841828 -0.0401362 -0.119092 0.0771649 -0.0395028 -0.125273 0.0740657 -0.0401362 -0.128137 0.0689917 -0.0401362 -0.135182 0.0538966 -0.0401362 -0.140137 0.0392519 -0.0401362 -0.133638 0.0477321 -0.0395028 -0.142433 0.0298628 -0.0401362 -0.144031 0.0208317 -0.0401362 -0.144596 0.016461 -0.0401362 -0.145018 0.0121908 -0.0401362 -0.140996 0.0160512 -0.0395028 -0.141408 0.0118873 -0.0395028 -0.145476 0.00395927 -0.0401362 -0.145309 0.00802313 -0.0401362 -0.14028 0 -0.039046 -0.141691 -0.00782337 -0.0395028 -0.141408 -0.0118873 -0.0395028 -0.138887 -0.0291193 -0.0395028 -0.137858 -0.0336558 -0.0395028 -0.136647 -0.0382746 -0.0395028 -0.133638 -0.0477321 -0.0395028 -0.131816 -0.0525547 -0.0395028 -0.127481 -0.0623376 -0.0395028 -0.118799 -0.0639641 -0.0368012 -0.116144 -0.0686683 -0.0368012 -0.119105 -0.0704193 -0.0383714 -0.122154 -0.0722215 -0.0395028 -0.113233 -0.0733684 -0.0368012 -0.11006 -0.0780482 -0.0368012 -0.112866 -0.0800384 -0.0383714 -0.115755 -0.0820868 -0.0395028 -0.106617 -0.0826898 -0.0368012 -0.102897 -0.0872742 -0.0368012 -0.105521 -0.0894997 -0.0383714 -0.108222 -0.0917902 -0.0395028 -0.10142 -0.0941215 -0.0383714 -0.094617 -0.0961889 -0.0368012 -0.0900523 -0.100475 -0.0368012 -0.0923487 -0.103037 -0.0383714 -0.0947121 -0.105674 -0.0395028 -0.0873787 -0.107284 -0.0383714 -0.0800817 -0.108589 -0.0368012 -0.0746859 -0.112369 -0.0368012 -0.0765904 -0.115234 -0.0383714 -0.0690273 -0.115931 -0.0368012 -0.0725991 -0.121929 -0.0395028 -0.0584236 -0.125426 -0.0383714 -0.0518945 -0.128265 -0.0383714 -0.044037 -0.127536 -0.0368012 -0.0372917 -0.129669 -0.0368012 -0.0382427 -0.132975 -0.0383714 -0.0303926 -0.131457 -0.0368012 -0.0311676 -0.134809 -0.0383714 -0.023366 -0.132886 -0.0368012 -0.0245751 -0.139762 -0.0395028 -0.00185717 -0.138353 -0.0383714 0.0055695 -0.138253 -0.0383714 0.0129721 -0.137756 -0.0383714 0.020319 -0.136865 -0.0383714 0.0268935 -0.132217 -0.0368012 0.0338598 -0.130607 -0.0368012 0.0347232 -0.133938 -0.0383714 0.0406852 -0.128644 -0.0368012 0.0427904 -0.135301 -0.0395028 0.0616047 -0.123894 -0.0383714 0.066103 -0.117623 -0.0368012 0.0718888 -0.114178 -0.0368012 0.0756087 -0.120086 -0.0395028 0.0847866 -0.109344 -0.0383714 0.09237 -0.0983487 -0.0368012 0.0947255 -0.100857 -0.0383714 0.0876642 -0.102565 -0.0368012 0.0971497 -0.103438 -0.0395028 0.0967932 -0.0939988 -0.0368012 0.100933 -0.0895387 -0.0368012 0.103507 -0.0918219 -0.0383714 0.106156 -0.0941718 -0.0395028 0.107464 -0.0871577 -0.0383714 0.11398 -0.0845339 -0.0395028 0.114528 -0.0776426 -0.0383714 0.111136 -0.0824245 -0.0383714 0.120657 -0.0746948 -0.0395028 0.117503 -0.0663157 -0.0368012 0.120034 -0.0616151 -0.0368012 0.123095 -0.0631863 -0.0383714 0.126246 -0.0648034 -0.0395028 0.128655 -0.0598783 -0.0395028 0.127852 -0.0431118 -0.0368012 0.123115 -0.0464961 -0.0348514 0.124704 -0.0420502 -0.0348514 0.132755 -0.0501365 -0.0395028 0.134467 -0.0453426 -0.0395028 0.135971 -0.0406128 -0.0395028 0.137276 -0.0359553 -0.0395028 0.138394 -0.0313769 -0.0395028 0.139337 -0.0268835 -0.0395028 0.140115 -0.0224799 -0.0395028 0.140738 -0.01817 -0.0395028 0.141218 -0.0139569 -0.0395028 0.141565 -0.00984275 -0.0395028 0.141787 -0.00582931 -0.0395028 0.141893 -0.00191757 -0.0395028 0.141893 0.00191757 -0.0395028 0.141787 0.00582931 -0.0395028 0.141565 0.00984275 -0.0395028 0.141218 0.0139569 -0.0395028 0.140738 0.01817 -0.0395028 0.140115 0.0224799 -0.0395028 0.139337 0.0268835 -0.0395028 0.138394 0.0313769 -0.0395028 0.137276 0.0359553 -0.0395028 0.135971 0.0406128 -0.0395028 0.134467 0.0453426 -0.0395028 0.132755 0.0501365 -0.0395028 0.130821 0.0549853 -0.0395028 0.128655 0.0598783 -0.0395028 0.123583 0.0697472 -0.0395028 0.117646 0.0728309 -0.0383714 0.120499 0.0680068 -0.0383714 0.117459 0.0796296 -0.0395028 0.110214 0.0893882 -0.0395028 0.0967932 0.0939988 -0.0368012 0.09237 0.0983487 -0.0368012 0.0971497 0.103438 -0.0395028 0.0847866 0.109344 -0.0383714 0.0774173 0.110505 -0.0368012 0.0718888 0.114178 -0.0368012 0.0756087 0.120086 -0.0395028 0.0616047 0.123894 -0.0383714 0.055186 0.126884 -0.0383714 0.0473443 0.126346 -0.0368012 0.0406852 0.128644 -0.0368012 0.0417227 0.131925 -0.0383714 0.0338598 0.130607 -0.0368012 0.0347232 0.133938 -0.0383714 0.0268935 0.132217 -0.0368012 0.0282851 0.139059 -0.0395028 -0.00185717 0.138353 -0.0383714 -0.00927582 0.138054 -0.0383714 -0.0166545 0.137359 -0.0383714 -0.0239619 0.136275 -0.0383714 -0.0303926 0.131457 -0.0368012 -0.0372917 0.129669 -0.0368012 -0.0382427 0.132975 -0.0383714 -0.044037 0.127536 -0.0368012 -0.0463157 0.134135 -0.0395028 -0.0584236 0.125426 -0.0383714 -0.064727 0.122292 -0.0383714 -0.0690273 0.115931 -0.0368012 -0.0746859 0.112369 -0.0368012 -0.0785505 0.118183 -0.0395028 -0.085206 0.104617 -0.0368012 -0.0900523 0.100475 -0.0368012 -0.0947121 0.105674 -0.0395028 -0.0988985 0.0917811 -0.0368012 -0.102897 0.0872742 -0.0368012 -0.105521 0.0894997 -0.0383714 -0.108222 0.0917902 -0.0395028 -0.106617 0.0826898 -0.0368012 -0.11006 0.0780482 -0.0368012 -0.112866 0.0800384 -0.0383714 -0.115755 0.0820868 -0.0395028 -0.113284 0.0669775 -0.0348514 -0.115874 0.0623891 -0.0348514 -0.118799 0.0639641 -0.0368012 -0.122154 0.0722215 -0.0395028 -0.124947 0.0672739 -0.0395028 -0.121209 0.0592707 -0.0368012 -0.123383 0.0546016 -0.0368012 -0.126529 0.055994 -0.0383714 -0.129767 0.057427 -0.0395028 -0.131816 0.0525547 -0.0395028 -0.137858 0.0336558 -0.0395028 -0.137477 0.0156507 -0.0383714 -0.137879 0.0115907 -0.0383714 -0.141691 0.00782337 -0.0395028 -0.141854 0.00386068 -0.0395028 -0.124739 0 -0.0294625 -0.122537 0 -0.0273282 -0.122481 -0.00333343 -0.0273172 -0.138155 -0.00762815 -0.0383714 -0.125339 -0.00341122 -0.0300502 -0.128369 -0.00349369 -0.0325813 -0.127046 0 -0.0314829 -0.127094 -0.0183821 -0.0325813 -0.135421 -0.0283927 -0.0383714 -0.134418 -0.032816 -0.0383714 -0.122245 -0.0487387 -0.0348514 -0.120934 -0.0431947 -0.0325813 -0.119285 -0.0475588 -0.0325813 -0.130303 -0.046541 -0.0383714 -0.115874 -0.0623891 -0.0348514 -0.115363 -0.0564118 -0.0325813 -0.113069 -0.0608788 -0.0325813 -0.1243 -0.0607821 -0.0383714 -0.121829 -0.0655952 -0.0383714 -0.116121 -0.0752393 -0.0383714 -0.109335 -0.0847984 -0.0383714 -0.0964634 -0.0895212 -0.0348514 -0.0922873 -0.0938205 -0.0348514 -0.0970298 -0.0986418 -0.0383714 -0.083108 -0.102041 -0.0348514 -0.0781099 -0.105915 -0.0348514 -0.0821238 -0.111358 -0.0383714 -0.0631175 -0.119251 -0.0368012 -0.055568 -0.119296 -0.0348514 -0.0493581 -0.121996 -0.0348514 -0.0506041 -0.125076 -0.0368012 -0.0429527 -0.124396 -0.0348514 -0.04516 -0.130788 -0.0383714 -0.0162404 -0.133944 -0.0368012 -0.00904517 -0.134621 -0.0368012 -0.00181099 -0.134913 -0.0368012 0.00529728 -0.131496 -0.0348514 0.0123381 -0.131023 -0.0348514 0.0126496 -0.13433 -0.0368012 0.0193259 -0.130176 -0.0348514 0.0198138 -0.133462 -0.0368012 0.0262313 -0.128962 -0.0348514 0.0275793 -0.135589 -0.0383714 0.0473443 -0.126346 -0.0368012 0.0538138 -0.123729 -0.0368012 0.0585936 -0.117839 -0.0348514 0.0644754 -0.114726 -0.0348514 0.0677886 -0.120622 -0.0383714 0.0774173 -0.110505 -0.0368012 0.0806425 -0.104 -0.0348514 0.0855057 -0.10004 -0.0348514 0.0898996 -0.105181 -0.0383714 0.0992614 -0.0963958 -0.0383714 0.102212 -0.0828977 -0.0348514 0.105704 -0.0783959 -0.0348514 0.108372 -0.0803749 -0.0368012 0.10893 -0.0738477 -0.0348514 0.111896 -0.0692712 -0.0348514 0.114721 -0.0710199 -0.0368012 0.117646 -0.0728309 -0.0383714 0.120499 -0.0680068 -0.0383714 0.125444 -0.0583841 -0.0383714 0.127556 -0.0536132 -0.0383714 0.129442 -0.0488854 -0.0383714 0.131112 -0.0442111 -0.0383714 0.132578 -0.0395994 -0.0383714 0.13385 -0.0350581 -0.0383714 0.134941 -0.030594 -0.0383714 0.13586 -0.0262127 -0.0383714 0.137226 -0.0177166 -0.0383714 0.137695 -0.0136086 -0.0383714 0.138032 -0.00959713 -0.0383714 0.138249 -0.00568385 -0.0383714 0.138353 -0.00186972 -0.0383714 0.138353 0.00186972 -0.0383714 0.138249 0.00568385 -0.0383714 0.138032 0.00959713 -0.0383714 0.137695 0.0136086 -0.0383714 0.137226 0.0177166 -0.0383714 0.136618 0.021919 -0.0383714 0.13586 0.0262127 -0.0383714 0.134941 0.030594 -0.0383714 0.13385 0.0350581 -0.0383714 0.132578 0.0395994 -0.0383714 0.131112 0.0442111 -0.0383714 0.129442 0.0488854 -0.0383714 0.117079 0.060098 -0.0348514 0.11461 0.0646828 -0.0348514 0.117503 0.0663157 -0.0368012 0.111896 0.0692712 -0.0348514 0.10893 0.0738477 -0.0348514 0.11168 0.0757119 -0.0368012 0.105704 0.0783959 -0.0348514 0.102212 0.0828977 -0.0348514 0.104792 0.0849904 -0.0368012 0.100933 0.0895387 -0.0368012 0.0992614 0.0963958 -0.0383714 0.0876642 0.102565 -0.0368012 0.0806425 0.104 -0.0348514 0.0755111 0.107784 -0.0348514 0.0793914 0.113322 -0.0383714 0.066103 0.117623 -0.0368012 0.0585936 0.117839 -0.0348514 0.0524887 0.120682 -0.0348514 0.0538138 0.123729 -0.0368012 0.0461785 0.123235 -0.0348514 0.0485516 0.129567 -0.0383714 0.0198138 0.133462 -0.0368012 0.0126496 0.13433 -0.0368012 0.00543101 0.134815 -0.0368012 -0.00181099 0.134913 -0.0368012 -0.00882245 0.131306 -0.0348514 -0.0158405 0.130646 -0.0348514 -0.0162404 0.133944 -0.0368012 -0.0227907 0.129614 -0.0348514 -0.023366 0.132886 -0.0368012 -0.0296442 0.12822 -0.0348514 -0.0311676 0.134809 -0.0383714 -0.0506041 0.125076 -0.0368012 -0.055568 0.119296 -0.0348514 -0.0615634 0.116315 -0.0348514 -0.0631175 0.119251 -0.0368012 -0.0673277 0.113076 -0.0348514 -0.0707875 0.118887 -0.0383714 -0.0781099 0.105915 -0.0348514 -0.083108 0.102041 -0.0348514 -0.0873787 0.107284 -0.0383714 -0.0922873 0.0938205 -0.0348514 -0.0964634 0.0895212 -0.0348514 -0.10142 0.0941215 -0.0383714 -0.109335 0.0847984 -0.0383714 -0.116121 0.0752393 -0.0383714 -0.119105 0.0704193 -0.0383714 -0.121829 0.0655952 -0.0383714 -0.1243 0.0607821 -0.0383714 -0.128527 0.0512433 -0.0383714 -0.124753 0.0304565 -0.0325813 -0.125684 0.0263512 -0.0325813 -0.128802 0.0270049 -0.0348514 -0.133237 0.0373195 -0.0383714 -0.130247 0.0188381 -0.0348514 -0.133535 0.0193137 -0.0368012 -0.129599 0.0228789 -0.0348514 -0.134059 0.0152615 -0.0368012 -0.13445 0.0113025 -0.0368012 -0.138314 0.00376435 -0.0383714 -0.138155 0.00762815 -0.0383714 -0.131554 -0.00358036 -0.0348514 -0.13472 -0.00743846 -0.0368012 -0.13445 -0.0113025 -0.0368012 -0.13287 -0.0234565 -0.0368012 -0.132054 -0.0276866 -0.0368012 -0.131075 -0.032 -0.0368012 -0.129924 -0.0363915 -0.0368012 -0.128591 -0.0408551 -0.0368012 -0.127063 -0.0453837 -0.0368012 -0.125331 -0.049969 -0.0368012 -0.123383 -0.0546016 -0.0368012 -0.121209 -0.0592707 -0.0368012 -0.110542 -0.0653561 -0.0325813 -0.107771 -0.0698296 -0.0325813 -0.110445 -0.0715619 -0.0348514 -0.104751 -0.0742836 -0.0325813 -0.101474 -0.0787013 -0.0325813 -0.103991 -0.0806538 -0.0348514 -0.100364 -0.0851253 -0.0348514 -0.0988985 -0.0917811 -0.0368012 -0.0857087 -0.0956289 -0.0325813 -0.0810961 -0.0995705 -0.0325813 -0.085206 -0.104617 -0.0368012 -0.0728469 -0.109602 -0.0348514 -0.0656978 -0.110339 -0.0325813 -0.0600731 -0.113499 -0.0325813 -0.0615634 -0.116315 -0.0348514 -0.0542229 -0.116408 -0.0325813 -0.0569708 -0.122307 -0.0368012 -0.0363735 -0.126476 -0.0348514 -0.0296442 -0.12822 -0.0348514 -0.0227907 -0.129614 -0.0348514 -0.00860888 -0.128128 -0.0325813 -0.00882245 -0.131306 -0.0348514 -0.015457 -0.127483 -0.0325813 -0.00172364 -0.128405 -0.0325813 -0.0017664 -0.131591 -0.0348514 0.00516905 -0.128313 -0.0325813 0.00543101 -0.134815 -0.0368012 0.033026 -0.127391 -0.0348514 0.0396834 -0.125477 -0.0348514 0.0512181 -0.117761 -0.0325813 0.0524887 -0.120682 -0.0348514 0.0450607 -0.120251 -0.0325813 0.0571752 -0.114986 -0.0325813 0.0600728 -0.120814 -0.0368012 0.0701187 -0.111367 -0.0348514 0.0786903 -0.101482 -0.0325813 0.0736831 -0.105174 -0.0325813 0.0826783 -0.106625 -0.0368012 0.0879146 -0.0936049 -0.0325813 0.0921244 -0.0894648 -0.0325813 0.0944099 -0.0916843 -0.0348514 0.098448 -0.087334 -0.0348514 0.104792 -0.0849904 -0.0368012 0.11168 -0.0757119 -0.0368012 0.118385 -0.0497584 -0.0325813 0.113676 -0.0529071 -0.0300502 0.11559 -0.0485838 -0.0300502 0.122325 -0.0569323 -0.0368012 0.124384 -0.0522801 -0.0368012 0.126223 -0.0476698 -0.0368012 0.129281 -0.0386147 -0.0368012 0.130522 -0.0341863 -0.0368012 0.131585 -0.0298332 -0.0368012 0.130964 -0.0129434 -0.0348514 0.134271 -0.0132702 -0.0368012 0.130519 -0.0168507 -0.0348514 0.133814 -0.0172761 -0.0368012 0.1346 -0.00935849 -0.0368012 0.134811 -0.00554251 -0.0368012 0.134912 -0.00182322 -0.0368012 0.134912 0.00182322 -0.0368012 0.134811 0.00554251 -0.0368012 0.1346 0.00935849 -0.0368012 0.134271 0.0132702 -0.0368012 0.133814 0.0172761 -0.0368012 0.133221 0.0213739 -0.0368012 0.132481 0.0255609 -0.0368012 0.131585 0.0298332 -0.0368012 0.130522 0.0341863 -0.0368012 0.129281 0.0386147 -0.0368012 0.127852 0.0431118 -0.0368012 0.118385 0.0497584 -0.0325813 0.116425 0.0541862 -0.0325813 0.119313 0.0555305 -0.0348514 0.122325 0.0569323 -0.0368012 0.120034 0.0616151 -0.0368012 0.114721 0.0710199 -0.0368012 0.108372 0.0803749 -0.0368012 0.0921244 0.0894648 -0.0325813 0.0944099 0.0916843 -0.0348514 0.0960648 0.0852198 -0.0325813 0.0900956 0.0959271 -0.0348514 0.0786903 0.101482 -0.0325813 0.0834358 0.0976183 -0.0325813 0.0826783 0.106625 -0.0368012 0.0701187 0.111367 -0.0348514 0.0571752 0.114986 -0.0325813 0.0629146 0.111949 -0.0325813 0.0600728 0.120814 -0.0368012 0.0396834 0.125477 -0.0348514 0.033026 0.127391 -0.0348514 0.0262313 0.128962 -0.0348514 0.0120394 0.127851 -0.0325813 0.0123381 0.131023 -0.0348514 0.0188581 0.127025 -0.0325813 0.00516905 0.128313 -0.0325813 0.00529728 0.131496 -0.0348514 -0.00172364 0.128405 -0.0325813 -0.0017664 0.131591 -0.0348514 -0.00860888 0.128128 -0.0325813 -0.00904517 0.134621 -0.0368012 -0.0363735 0.126476 -0.0348514 -0.0429527 0.124396 -0.0348514 -0.0542229 0.116408 -0.0325813 -0.0481633 0.119043 -0.0325813 -0.0569708 0.122307 -0.0368012 -0.0710835 0.106949 -0.0325813 -0.0762191 0.103351 -0.0325813 -0.0800817 0.108589 -0.0368012 -0.087835 0.0980012 -0.0348514 -0.094617 0.0961889 -0.0368012 -0.0979343 0.0830646 -0.0325813 -0.101474 0.0787013 -0.0325813 -0.103991 0.0806538 -0.0348514 -0.104751 0.0742836 -0.0325813 -0.107771 0.0698296 -0.0325813 -0.110445 0.0715619 -0.0348514 -0.113233 0.0733684 -0.0368012 -0.116144 0.0686683 -0.0368012 -0.120934 0.0431947 -0.0325813 -0.11647 0.0464362 -0.0300502 -0.118079 0.042175 -0.0300502 -0.125331 0.049969 -0.0368012 -0.127063 0.0453837 -0.0368012 -0.128591 0.0408551 -0.0368012 -0.129924 0.0363915 -0.0368012 -0.131075 0.032 -0.0368012 -0.13114 0.0110242 -0.0348514 -0.134875 0.00367074 -0.0368012 -0.13472 0.00743846 -0.0368012 -0.129463 0 -0.0333707 -0.131402 -0.00725531 -0.0348514 -0.13114 -0.0110242 -0.0348514 -0.129599 -0.0228789 -0.0348514 -0.128802 -0.0270049 -0.0348514 -0.127848 -0.0312121 -0.0348514 -0.126725 -0.0354954 -0.0348514 -0.125424 -0.0398491 -0.0348514 -0.123934 -0.0442662 -0.0348514 -0.120345 -0.0532572 -0.0348514 -0.118225 -0.0578113 -0.0348514 -0.113284 -0.0669775 -0.0348514 -0.10735 -0.0761264 -0.0348514 -0.0956225 -0.0811038 -0.0300502 -0.0919063 -0.0852921 -0.0300502 -0.0941282 -0.0873541 -0.0325813 -0.0900532 -0.0915493 -0.0325813 -0.087835 -0.0980012 -0.0348514 -0.0762191 -0.103351 -0.0325813 -0.0694055 -0.104424 -0.0300502 -0.064147 -0.107734 -0.0300502 -0.0673277 -0.113076 -0.0348514 -0.0481633 -0.119043 -0.0325813 -0.0419129 -0.121384 -0.0325813 -0.0289266 -0.125116 -0.0325813 -0.0346551 -0.120501 -0.0300502 -0.0282438 -0.122163 -0.0300502 -0.022239 -0.126476 -0.0325813 -0.021714 -0.123491 -0.0300502 -0.0150922 -0.124474 -0.0300502 -0.0158405 -0.130646 -0.0348514 0.0120394 -0.127851 -0.0325813 0.0188581 -0.127025 -0.0325813 0.0255963 -0.12584 -0.0325813 0.0387228 -0.122439 -0.0325813 0.0314658 -0.121373 -0.0300502 0.0378087 -0.119549 -0.0300502 0.043997 -0.117413 -0.0300502 0.0461785 -0.123235 -0.0348514 0.0629146 -0.111949 -0.0325813 0.0668062 -0.106106 -0.0300502 0.0719438 -0.102692 -0.0300502 0.0755111 -0.107784 -0.0348514 0.0814662 -0.095314 -0.0300502 0.0858393 -0.0913953 -0.0300502 0.0900956 -0.0959271 -0.0348514 0.0937971 -0.0832082 -0.0300502 0.0973829 -0.0789815 -0.0300502 0.0997372 -0.080891 -0.0325813 0.10071 -0.0746923 -0.0300502 0.103784 -0.070359 -0.0300502 0.106293 -0.07206 -0.0325813 0.10661 -0.0659987 -0.0300502 0.109195 -0.0616271 -0.0300502 0.111835 -0.063117 -0.0325813 0.11461 -0.0646828 -0.0348514 0.117079 -0.060098 -0.0348514 0.119313 -0.0555305 -0.0348514 0.121322 -0.0509928 -0.0348514 0.119494 -0.0270918 -0.0273172 0.116891 -0.0265018 -0.0244418 0.120308 -0.0232121 -0.0273172 0.126098 -0.0376639 -0.0348514 0.127308 -0.0333446 -0.0348514 0.128345 -0.0290986 -0.0348514 0.129219 -0.0249315 -0.0348514 0.129941 -0.0208477 -0.0348514 0.131286 -0.00912806 -0.0348514 0.131491 -0.00540604 -0.0348514 0.131591 -0.00177833 -0.0348514 0.131591 0.00177833 -0.0348514 0.131491 0.00540604 -0.0348514 0.131286 0.00912806 -0.0348514 0.130964 0.0129434 -0.0348514 0.123802 0.0198628 -0.0300502 0.123115 0.0237537 -0.0300502 0.126091 0.024328 -0.0325813 0.130519 0.0168507 -0.0348514 0.129941 0.0208477 -0.0348514 0.129219 0.0249315 -0.0348514 0.128345 0.0290986 -0.0348514 0.127308 0.0333446 -0.0348514 0.126098 0.0376639 -0.0348514 0.123115 0.0464961 -0.0348514 0.121322 0.0509928 -0.0348514 0.109195 0.0616271 -0.0300502 0.10661 0.0659987 -0.0300502 0.109187 0.0675943 -0.0325813 0.103784 0.070359 -0.0300502 0.10071 0.0746923 -0.0300502 0.103145 0.0764981 -0.0325813 0.0973829 0.0789815 -0.0300502 0.0937971 0.0832082 -0.0300502 0.098448 0.087334 -0.0348514 0.0858393 0.0913953 -0.0300502 0.0814662 0.095314 -0.0300502 0.0855057 0.10004 -0.0348514 0.0736831 0.105174 -0.0325813 0.0668062 0.106106 -0.0300502 0.0614294 0.109307 -0.0300502 0.0644754 0.114726 -0.0348514 0.0512181 0.117761 -0.0325813 0.0450607 0.120251 -0.0325813 0.0322266 0.124307 -0.0325813 0.0378087 0.119549 -0.0300502 0.0314658 0.121373 -0.0300502 0.0255963 0.12584 -0.0325813 0.0249921 0.122869 -0.0300502 0.0184129 0.124026 -0.0300502 0.0193259 0.130176 -0.0348514 -0.015457 0.127483 -0.0325813 -0.022239 0.126476 -0.0325813 -0.0289266 0.125116 -0.0325813 -0.0419129 0.121384 -0.0325813 -0.0346551 0.120501 -0.0300502 -0.0409236 0.118519 -0.0300502 -0.0470263 0.116233 -0.0300502 -0.0493581 0.121996 -0.0348514 -0.0600731 0.113499 -0.0325813 -0.064147 0.107734 -0.0300502 -0.0694055 0.104424 -0.0300502 -0.0728469 0.109602 -0.0348514 -0.0810961 0.0995705 -0.0325813 -0.0836855 0.0933715 -0.0300502 -0.0879275 0.0893882 -0.0300502 -0.0900532 0.0915493 -0.0325813 -0.0941282 0.0873541 -0.0325813 -0.100364 0.0851253 -0.0348514 -0.10735 0.0761264 -0.0348514 -0.1104 0.0594417 -0.0300502 -0.11264 0.0550802 -0.0300502 -0.115363 0.0564118 -0.0325813 -0.118225 0.0578113 -0.0348514 -0.120345 0.0532572 -0.0348514 -0.122245 0.0487387 -0.0348514 -0.123934 0.0442662 -0.0348514 -0.125424 0.0398491 -0.0348514 -0.126725 0.0354954 -0.0348514 -0.127848 0.0312121 -0.0348514 -0.127965 0.0107573 -0.0325813 -0.131554 0.00358036 -0.0348514 -0.131402 0.00725531 -0.0348514 -0.128221 -0.00707967 -0.0325813 -0.119089 -0.0135572 -0.0244418 -0.121265 -0.0175389 -0.0273172 -0.126461 -0.0223251 -0.0325813 -0.125684 -0.0263512 -0.0325813 -0.124753 -0.0304565 -0.0325813 -0.123658 -0.0346362 -0.0325813 -0.122388 -0.0388845 -0.0325813 -0.105464 -0.0515712 -0.021483 -0.105533 -0.0568212 -0.0244418 -0.107674 -0.052652 -0.0244418 -0.117432 -0.051968 -0.0325813 -0.107932 -0.0638133 -0.0300502 -0.107883 -0.0580864 -0.0273172 -0.105471 -0.0623583 -0.0273172 -0.102278 -0.0725301 -0.0300502 -0.102828 -0.0666266 -0.0273172 -0.0999463 -0.0708763 -0.0273172 -0.0968195 -0.0750914 -0.0273172 -0.0934422 -0.0792545 -0.0273172 -0.0979343 -0.0830646 -0.0325813 -0.0836855 -0.0933715 -0.0300502 -0.0859226 -0.0873501 -0.0273172 -0.0817773 -0.0912425 -0.0273172 -0.0791818 -0.09722 -0.0300502 -0.072723 -0.0986108 -0.0273172 -0.067823 -0.102043 -0.0273172 -0.0710835 -0.106949 -0.0325813 -0.058655 -0.11082 -0.0300502 -0.0529429 -0.11366 -0.0300502 -0.0409236 -0.118519 -0.0300502 -0.045954 -0.113582 -0.0273172 -0.0399904 -0.115817 -0.0273172 -0.033865 -0.117753 -0.0273172 -0.035493 -0.123414 -0.0325813 -0.00840566 -0.125103 -0.0300502 -0.00168295 -0.125374 -0.0300502 0.00504703 -0.125284 -0.0300502 0.0184129 -0.124026 -0.0300502 0.0114872 -0.121987 -0.0273172 0.0179931 -0.121198 -0.0273172 0.0249921 -0.122869 -0.0300502 0.0244222 -0.120068 -0.0273172 0.0307484 -0.118605 -0.0273172 0.0322266 -0.124307 -0.0325813 0.0500091 -0.114981 -0.0300502 0.0558256 -0.112272 -0.0300502 0.0600287 -0.106814 -0.0273172 0.0652829 -0.103686 -0.0273172 0.0684213 -0.108671 -0.0325813 0.0768328 -0.0990869 -0.0300502 0.0834358 -0.0976183 -0.0325813 0.0878988 -0.0853612 -0.0273172 0.0916584 -0.0813109 -0.0273172 0.0960648 -0.0852198 -0.0325813 0.103145 -0.0764981 -0.0325813 0.109187 -0.0675943 -0.0325813 0.114245 -0.0586432 -0.0325813 0.116425 -0.0541862 -0.0325813 0.120135 -0.0453705 -0.0325813 0.121685 -0.0410323 -0.0325813 0.123045 -0.0367521 -0.0325813 0.124226 -0.0325374 -0.0325813 0.125238 -0.0283942 -0.0325813 0.126091 -0.024328 -0.0325813 0.126795 -0.020343 -0.0325813 0.12736 -0.0164428 -0.0325813 0.127794 -0.0126301 -0.0325813 0.128107 -0.00890709 -0.0325813 0.128308 -0.00527517 -0.0325813 0.128405 -0.00173528 -0.0325813 0.128405 0.00173528 -0.0325813 0.128308 0.00527517 -0.0325813 0.128107 0.00890709 -0.0325813 0.127794 0.0126301 -0.0325813 0.12736 0.0164428 -0.0325813 0.126795 0.020343 -0.0325813 0.125238 0.0283942 -0.0325813 0.124226 0.0325374 -0.0325813 0.104442 0.0536111 -0.021483 0.106435 0.0495366 -0.021483 0.104409 0.048594 -0.0185002 0.120135 0.0453705 -0.0325813 0.111084 0.0517008 -0.0273172 0.109004 0.0559533 -0.0273172 0.111548 0.0572589 -0.0300502 0.114245 0.0586432 -0.0325813 0.111835 0.063117 -0.0325813 0.106293 0.07206 -0.0325813 0.0997372 0.080891 -0.0325813 0.0878988 0.0853612 -0.0273172 0.0838821 0.0893114 -0.0273172 0.0879146 0.0936049 -0.0325813 0.0768328 0.0990869 -0.0300502 0.0703034 0.10035 -0.0273172 0.0652829 0.103686 -0.0273172 0.0684213 0.108671 -0.0325813 0.0558256 0.112272 -0.0300502 0.043997 0.117413 -0.0300502 0.0488688 0.112359 -0.0273172 0.0429938 0.114736 -0.0273172 0.0369466 0.116823 -0.0273172 0.0387228 0.122439 -0.0325813 0.0117552 0.124833 -0.0300502 0.00504703 0.125284 -0.0300502 -0.00168295 0.125374 -0.0300502 -0.00840566 0.125103 -0.0300502 -0.021714 0.123491 -0.0300502 -0.014748 0.121636 -0.0273172 -0.0212189 0.120675 -0.0273172 -0.0282438 0.122163 -0.0300502 -0.0275998 0.119377 -0.0273172 -0.033865 0.117753 -0.0273172 -0.035493 0.123414 -0.0325813 -0.0529429 0.11366 -0.0300502 -0.0573176 0.108293 -0.0273172 -0.0626843 0.105278 -0.0273172 -0.0656978 0.110339 -0.0325813 -0.0744199 0.100912 -0.0300502 -0.0773763 0.0950033 -0.0273172 -0.0817773 0.0912425 -0.0273172 -0.0857087 0.0956289 -0.0325813 -0.0956225 0.0811038 -0.0300502 -0.0898107 0.0833473 -0.0273172 -0.0934422 0.0792545 -0.0273172 -0.102278 0.0725301 -0.0300502 -0.0968195 0.0750914 -0.0273172 -0.0999463 0.0708763 -0.0273172 -0.107932 0.0638133 -0.0300502 -0.102828 0.0666266 -0.0273172 -0.105471 0.0623583 -0.0273172 -0.110542 0.0653561 -0.0325813 -0.113069 0.0608788 -0.0325813 -0.117432 0.051968 -0.0325813 -0.119285 0.0475588 -0.0325813 -0.122388 0.0388845 -0.0325813 -0.123658 0.0346362 -0.0325813 -0.124945 0.0105034 -0.0300502 -0.128221 0.00707967 -0.0325813 -0.128369 0.00349369 -0.0325813 -0.125195 -0.00691255 -0.0300502 -0.124094 -0.0179482 -0.0300502 -0.123476 -0.0217981 -0.0300502 -0.122717 -0.0257292 -0.0300502 -0.121808 -0.0297375 -0.0300502 -0.120739 -0.0338186 -0.0300502 -0.118079 -0.042175 -0.0300502 -0.11647 -0.0464362 -0.0300502 -0.11466 -0.0507412 -0.0300502 -0.11264 -0.0550802 -0.0300502 -0.1104 -0.0594417 -0.0300502 -0.105227 -0.0681812 -0.0300502 -0.0990786 -0.0768435 -0.0300502 -0.0878546 -0.081532 -0.0244418 -0.0898107 -0.0833473 -0.0273172 -0.0879275 -0.0893882 -0.0300502 -0.0756911 -0.0929341 -0.0244418 -0.0773763 -0.0950033 -0.0273172 -0.0744199 -0.100912 -0.0300502 -0.0626843 -0.105278 -0.0273172 -0.0560692 -0.105935 -0.0244418 -0.0517357 -0.111068 -0.0273172 -0.0573176 -0.108293 -0.0273172 -0.0506089 -0.108649 -0.0244418 -0.0470263 -0.116233 -0.0300502 -0.0275998 -0.119377 -0.0273172 -0.0212189 -0.120675 -0.0273172 -0.014748 -0.121636 -0.0273172 -0.0080351 -0.119588 -0.0244418 -0.00164458 -0.122515 -0.0273172 -0.008214 -0.122251 -0.0273172 -0.00160876 -0.119847 -0.0244418 0.00493195 -0.122427 -0.0273172 0.00482453 -0.119761 -0.0244418 0.0117552 -0.124833 -0.0300502 0.0369466 -0.116823 -0.0273172 0.0429938 -0.114736 -0.0273172 0.0478044 -0.109912 -0.0244418 0.0545527 -0.109712 -0.0273172 0.0488688 -0.112359 -0.0273172 0.0533645 -0.107323 -0.0244418 0.0614294 -0.109307 -0.0300502 0.0703034 -0.10035 -0.0273172 0.0734456 -0.0947187 -0.0244418 0.0796086 -0.0931407 -0.0273172 0.0750809 -0.0968276 -0.0273172 0.0838821 -0.0893114 -0.0273172 0.0899498 -0.0873529 -0.0300502 0.0930898 -0.0754996 -0.0244418 0.0984139 -0.0729892 -0.0273172 0.0951624 -0.0771806 -0.0273172 0.0992086 -0.0672572 -0.0244418 0.104179 -0.0644938 -0.0273172 0.101418 -0.0687547 -0.0273172 0.105875 -0.0399852 -0.0155526 0.102741 -0.043183 -0.0126994 0.104259 -0.039375 -0.0126994 0.111548 -0.0572589 -0.0300502 0.10844 -0.0323898 -0.0155526 0.109481 -0.0286753 -0.0155526 0.111406 -0.0291794 -0.0185002 0.117299 -0.0442995 -0.0300502 0.118812 -0.0400637 -0.0300502 0.120141 -0.0358846 -0.0300502 0.121294 -0.0317693 -0.0300502 0.122282 -0.027724 -0.0300502 0.123115 -0.0237537 -0.0300502 0.123802 -0.0198628 -0.0300502 0.124353 -0.0160546 -0.0300502 0.124777 -0.012332 -0.0300502 0.125083 -0.00869683 -0.0300502 0.12528 -0.00515065 -0.0300502 0.125374 -0.00169432 -0.0300502 0.125374 0.00169432 -0.0300502 0.12528 0.00515065 -0.0300502 0.125083 0.00869683 -0.0300502 0.124777 0.012332 -0.0300502 0.124353 0.0160546 -0.0300502 0.107736 0.0406881 -0.0185002 0.107241 0.0361619 -0.0155526 0.105875 0.0399852 -0.0155526 0.122282 0.027724 -0.0300502 0.121294 0.0317693 -0.0300502 0.120141 0.0358846 -0.0300502 0.118812 0.0400637 -0.0300502 0.117299 0.0442995 -0.0300502 0.11559 0.0485838 -0.0300502 0.113676 0.0529071 -0.0300502 0.10191 0.0630891 -0.0244418 0.101418 0.0687547 -0.0273172 0.104179 0.0644938 -0.0273172 0.0962705 0.0713995 -0.0244418 0.0951624 0.0771806 -0.0273172 0.0984139 0.0729892 -0.0273172 0.0916584 0.0813109 -0.0273172 0.0899498 0.0873529 -0.0300502 0.0796086 0.0931407 -0.0273172 0.0734456 0.0947187 -0.0244418 0.0750809 0.0968276 -0.0273172 0.0719438 0.102692 -0.0300502 0.0600287 0.106814 -0.0273172 0.0533645 0.107323 -0.0244418 0.0545527 0.109712 -0.0273172 0.0500091 0.114981 -0.0300502 0.0307484 0.118605 -0.0273172 0.0244222 0.120068 -0.0273172 0.0179931 0.121198 -0.0273172 0.011237 0.11933 -0.0244418 0.00493195 0.122427 -0.0273172 0.0114872 0.121987 -0.0273172 0.00482453 0.119761 -0.0244418 -0.00164458 0.122515 -0.0273172 -0.00160876 0.119847 -0.0244418 -0.008214 0.122251 -0.0273172 -0.0080351 0.119588 -0.0244418 -0.0150922 0.124474 -0.0300502 -0.0399904 0.115817 -0.0273172 -0.045954 0.113582 -0.0273172 -0.0506089 0.108649 -0.0244418 -0.0517357 0.111068 -0.0273172 -0.058655 0.11082 -0.0300502 -0.067823 0.102043 -0.0273172 -0.0711391 0.0964631 -0.0244418 -0.072723 0.0986108 -0.0273172 -0.0791818 0.09722 -0.0300502 -0.0840512 0.0854476 -0.0244418 -0.0859226 0.0873501 -0.0273172 -0.0919063 0.0852921 -0.0300502 -0.0990786 0.0768435 -0.0300502 -0.105227 0.0681812 -0.0300502 -0.107861 0.034269 -0.0155526 -0.104953 0.0374866 -0.0126994 -0.106215 0.033746 -0.0126994 -0.11466 0.0507412 -0.0300502 -0.115416 0.0323277 -0.0244418 -0.113047 0.0316641 -0.021483 -0.116438 0.0284266 -0.0244418 -0.119499 0.0379666 -0.0300502 -0.120739 0.0338186 -0.0300502 -0.121808 0.0297375 -0.0300502 -0.122717 0.0257292 -0.0300502 -0.120661 0.0213011 -0.0273172 -0.125339 0.00341122 -0.0300502 -0.125195 0.00691255 -0.0300502 -0.120436 0 -0.0250934 -0.12234 -0.00675494 -0.0273172 -0.120661 -0.0213011 -0.0273172 -0.119919 -0.0251425 -0.0273172 -0.119031 -0.0290595 -0.0273172 -0.114231 -0.0362928 -0.0244418 -0.115387 -0.0412134 -0.0273172 -0.113814 -0.0453774 -0.0273172 -0.112045 -0.0495842 -0.0273172 -0.110071 -0.0538242 -0.0273172 -0.0966491 -0.0626229 -0.0185002 -0.0957627 -0.0679095 -0.021483 -0.0985238 -0.0638376 -0.021483 -0.0910015 -0.0705791 -0.0185002 -0.0895308 -0.075937 -0.021483 -0.0927667 -0.0719481 -0.021483 -0.091407 -0.0775284 -0.0244418 -0.0799963 -0.0892552 -0.0244418 -0.0783542 -0.0874231 -0.021483 -0.0663458 -0.0998205 -0.0244418 -0.064984 -0.0977715 -0.021483 -0.0613191 -0.102985 -0.0244418 -0.0600604 -0.100871 -0.021483 -0.0449532 -0.111109 -0.0244418 -0.0331274 -0.115189 -0.0244418 -0.0324474 -0.112824 -0.021483 -0.0269987 -0.116777 -0.0244418 -0.0264445 -0.11438 -0.021483 -0.0207568 -0.118047 -0.0244418 -0.0203307 -0.115624 -0.021483 -0.0144268 -0.118986 -0.0244418 -0.0141307 -0.116544 -0.021483 0.011237 -0.11933 -0.0244418 0.0176012 -0.118558 -0.0244418 0.0300787 -0.116022 -0.0244418 0.0294613 -0.113641 -0.021483 0.0361419 -0.114279 -0.0244418 0.0354 -0.111933 -0.021483 0.0420574 -0.112237 -0.0244418 0.0411941 -0.109933 -0.021483 0.063861 -0.101428 -0.0244418 0.0625502 -0.0993462 -0.021483 0.0687722 -0.0981646 -0.0244418 0.0705692 -0.0910091 -0.0185002 0.0762763 -0.0892419 -0.021483 0.0719381 -0.0927745 -0.021483 0.0826169 -0.0802317 -0.0185002 0.0878216 -0.0779073 -0.021483 0.0842194 -0.081788 -0.021483 0.0896621 -0.07954 -0.0244418 0.106705 -0.0602219 -0.0273172 0.109004 -0.0559533 -0.0273172 0.111084 -0.0517008 -0.0273172 0.112955 -0.047476 -0.0273172 0.114624 -0.0432894 -0.0273172 0.116103 -0.0391502 -0.0273172 0.117401 -0.0350664 -0.0273172 0.118528 -0.0310449 -0.0273172 0.120979 -0.0194099 -0.0273172 0.121518 -0.0156886 -0.0273172 0.121932 -0.0120508 -0.0273172 0.122231 -0.00849853 -0.0273172 0.122423 -0.00503321 -0.0273172 0.122515 -0.00165569 -0.0273172 0.122515 0.00165569 -0.0273172 0.122423 0.00503321 -0.0273172 0.122231 0.00849853 -0.0273172 0.121932 0.0120508 -0.0273172 0.121518 0.0156886 -0.0273172 0.120979 0.0194099 -0.0273172 0.120308 0.0232121 -0.0273172 0.119494 0.0270918 -0.0273172 0.118528 0.0310449 -0.0273172 0.117401 0.0350664 -0.0273172 0.116103 0.0391502 -0.0273172 0.114624 0.0432894 -0.0273172 0.112955 0.047476 -0.0273172 0.0947586 0.0586619 -0.0126994 0.0922468 0.0625375 -0.0126994 0.0936764 0.0635068 -0.0155526 0.106705 0.0602219 -0.0273172 0.0826169 0.0802317 -0.0185002 0.0803708 0.0855729 -0.021483 0.0842194 0.081788 -0.021483 0.0820551 0.0873662 -0.0244418 0.0778748 0.0911121 -0.0244418 0.0705692 0.0910091 -0.0185002 0.0673605 0.0961496 -0.021483 0.0719381 0.0927745 -0.021483 0.063861 0.101428 -0.0244418 0.0625502 0.0993462 -0.021483 0.0587213 0.104488 -0.0244418 0.0512745 0.103119 -0.0185002 0.0468232 0.107656 -0.021483 0.0522691 0.10512 -0.021483 0.0478044 0.109912 -0.0244418 0.0361419 0.114279 -0.0244418 0.0354 0.111933 -0.021483 0.0300787 0.116022 -0.0244418 0.0294613 0.113641 -0.021483 0.0238903 0.117453 -0.0244418 0.0233999 0.115042 -0.021483 0.0176012 0.118558 -0.0244418 0.0172399 0.116125 -0.021483 -0.0144268 0.118986 -0.0244418 -0.0269987 0.116777 -0.0244418 -0.0264445 0.11438 -0.021483 -0.0331274 0.115189 -0.0244418 -0.0324474 0.112824 -0.021483 -0.0391195 0.113294 -0.0244418 -0.0383165 0.110969 -0.021483 -0.0449532 0.111109 -0.0244418 -0.0549184 0.10376 -0.021483 -0.0495701 0.106419 -0.021483 -0.0486269 0.104394 -0.0185002 -0.0560692 0.105935 -0.0244418 -0.0663458 0.0998205 -0.0244418 -0.064984 0.0977715 -0.021483 -0.0799963 0.0892552 -0.0244418 -0.0783542 0.0874231 -0.021483 -0.0910015 0.0705791 -0.0185002 -0.0957627 0.0679095 -0.021483 -0.0927667 0.0719481 -0.021483 -0.0966491 0.0626229 -0.0185002 -0.101056 0.059748 -0.021483 -0.0985238 0.0638376 -0.021483 -0.100118 0.0489572 -0.0126994 -0.101913 0.0451006 -0.0126994 -0.103493 0.0457995 -0.0155526 -0.107883 0.0580864 -0.0273172 -0.110071 0.0538242 -0.0273172 -0.112045 0.0495842 -0.0273172 -0.113814 0.0453774 -0.0273172 -0.115387 0.0412134 -0.0273172 -0.116774 0.0371009 -0.0273172 -0.117986 0.0330474 -0.0273172 -0.119031 0.0290595 -0.0273172 -0.119919 0.0251425 -0.0273172 -0.116985 0.00983423 -0.021483 -0.116644 0.013279 -0.021483 -0.122481 0.00333343 -0.0273172 -0.119676 -0.00660782 -0.0244418 -0.118623 -0.0171569 -0.0244418 -0.113047 -0.0316641 -0.021483 -0.114048 -0.0278431 -0.021483 -0.111878 -0.0273133 -0.0185002 -0.118033 -0.0208371 -0.0244418 -0.117307 -0.0245949 -0.0244418 -0.116438 -0.0284266 -0.0244418 -0.115416 -0.0323277 -0.0244418 -0.101913 -0.0451006 -0.0126994 -0.100118 -0.0489572 -0.0126994 -0.10167 -0.0497159 -0.0155526 -0.112874 -0.0403157 -0.0244418 -0.111335 -0.044389 -0.0244418 -0.109605 -0.0485043 -0.0244418 -0.103174 -0.0610002 -0.0244418 -0.100589 -0.0651754 -0.0244418 -0.0977695 -0.0693326 -0.0244418 -0.0947107 -0.0734559 -0.0244418 -0.0755354 -0.084278 -0.0155526 -0.0768633 -0.0857596 -0.0185002 -0.0793642 -0.0806827 -0.0155526 -0.0840512 -0.0854476 -0.0244418 -0.0696789 -0.094483 -0.021483 -0.068353 -0.0926852 -0.0185002 -0.0711391 -0.0964631 -0.0244418 -0.0495701 -0.106419 -0.021483 -0.0486269 -0.104394 -0.0185002 -0.0440305 -0.108828 -0.021483 -0.0431926 -0.106757 -0.0185002 -0.0383165 -0.110969 -0.021483 -0.0312801 -0.108766 -0.0155526 -0.03183 -0.110678 -0.0185002 -0.036938 -0.106976 -0.0155526 -0.0391195 -0.113294 -0.0244418 -0.00157574 -0.117387 -0.021483 -0.00154575 -0.115153 -0.0185002 0.0047255 -0.117302 -0.021483 0.00463558 -0.11507 -0.0185002 0.0110064 -0.11688 -0.021483 0.0107969 -0.114656 -0.0185002 0.0172399 -0.116125 -0.021483 0.0169119 -0.113915 -0.0185002 0.0233999 -0.115042 -0.021483 0.0229547 -0.112853 -0.0185002 0.0238903 -0.117453 -0.0244418 0.0522691 -0.10512 -0.021483 0.0512745 -0.103119 -0.0185002 0.057516 -0.102343 -0.021483 0.0564216 -0.100396 -0.0185002 0.0587213 -0.104488 -0.0244418 0.0774795 -0.0824943 -0.0155526 0.0788415 -0.0839446 -0.0185002 0.0735322 -0.0860314 -0.0155526 0.0778748 -0.0911121 -0.0244418 0.0820551 -0.0873662 -0.0244418 0.0859843 -0.083502 -0.0244418 0.0962272 -0.0595711 -0.0155526 0.0922468 -0.0625375 -0.0126994 0.0947586 -0.0586619 -0.0126994 0.0962705 -0.0713995 -0.0244418 0.100684 -0.0516824 -0.0155526 0.0970565 -0.0547763 -0.0126994 0.0991476 -0.0508937 -0.0126994 0.10191 -0.0630891 -0.0244418 0.104381 -0.0589103 -0.0244418 0.10663 -0.0547346 -0.0244418 0.108665 -0.0505747 -0.0244418 0.110495 -0.046442 -0.0244418 0.112128 -0.0423466 -0.0244418 0.113575 -0.0382975 -0.0244418 0.114844 -0.0343026 -0.0244418 0.115947 -0.0303688 -0.0244418 0.115915 -0.0185974 -0.021483 0.118871 -0.0153469 -0.0244418 0.118344 -0.0189871 -0.0244418 0.117687 -0.0227065 -0.0244418 0.119277 -0.0117883 -0.0244418 0.119569 -0.00831344 -0.0244418 0.119757 -0.00492358 -0.0244418 0.119847 -0.00161963 -0.0244418 0.119847 0.00161963 -0.0244418 0.119757 0.00492358 -0.0244418 0.119569 0.00831344 -0.0244418 0.119277 0.0117883 -0.0244418 0.118871 0.0153469 -0.0244418 0.118344 0.0189871 -0.0244418 0.117687 0.0227065 -0.0244418 0.116891 0.0265018 -0.0244418 0.115947 0.0303688 -0.0244418 0.114844 0.0343026 -0.0244418 0.113575 0.0382975 -0.0244418 0.112128 0.0423466 -0.0244418 0.110495 0.046442 -0.0244418 0.108665 0.0505747 -0.0244418 0.10663 0.0547346 -0.0244418 0.104381 0.0589103 -0.0244418 0.0878988 0.0712895 -0.0155526 0.0895148 0.0663891 -0.0126994 0.0865573 0.0702015 -0.0126994 0.0992086 0.0672572 -0.0244418 0.0846622 0.0751045 -0.0155526 0.0861505 0.0764248 -0.0185002 0.0930898 0.0754996 -0.0244418 0.0896621 0.07954 -0.0244418 0.0859843 0.083502 -0.0244418 0.0602999 0.0957721 -0.0155526 0.06136 0.0974558 -0.0185002 0.0649372 0.0926906 -0.0155526 0.0687722 0.0981646 -0.0244418 0.0459322 0.105607 -0.0185002 0.0411941 0.109933 -0.021483 0.0404102 0.107841 -0.0185002 0.0420574 0.112237 -0.0244418 0.0047255 0.117302 -0.021483 0.00463558 0.11507 -0.0185002 -0.00157574 0.117387 -0.021483 -0.00154575 0.115153 -0.0185002 -0.00787017 0.117133 -0.021483 -0.00772041 0.114905 -0.0185002 -0.0141307 0.116544 -0.021483 -0.0138618 0.114326 -0.0185002 -0.0203307 0.115624 -0.021483 -0.0199439 0.113424 -0.0185002 -0.0207568 0.118047 -0.0244418 -0.0538733 0.101786 -0.0185002 -0.0600604 0.100871 -0.021483 -0.0626461 0.0942542 -0.0155526 -0.0637474 0.0959111 -0.0185002 -0.0578997 0.097242 -0.0155526 -0.0613191 0.102985 -0.0244418 -0.0741374 0.0910265 -0.021483 -0.0727267 0.0892944 -0.0185002 -0.0756911 0.0929341 -0.0244418 -0.0863099 0.0732051 -0.0155526 -0.0878271 0.0744921 -0.0185002 -0.0829555 0.0769855 -0.0155526 -0.0878546 0.081532 -0.0244418 -0.091407 0.0775284 -0.0244418 -0.0947107 0.0734559 -0.0244418 -0.0977695 0.0693326 -0.0244418 -0.100589 0.0651754 -0.0244418 -0.103174 0.0610002 -0.0244418 -0.105533 0.0568212 -0.0244418 -0.107674 0.052652 -0.0244418 -0.109605 0.0485043 -0.0244418 -0.111335 0.044389 -0.0244418 -0.112874 0.0403157 -0.0244418 -0.114231 0.0362928 -0.0244418 -0.117307 0.0245949 -0.0244418 -0.119676 0.00660782 -0.0244418 -0.119813 0.00326083 -0.0244418 -0.116985 -0.00983423 -0.021483 -0.117219 -0.00647218 -0.021483 -0.116644 -0.013279 -0.021483 -0.116189 -0.0168048 -0.021483 -0.11561 -0.0204094 -0.021483 -0.114899 -0.02409 -0.021483 -0.111886 -0.0355479 -0.021483 -0.110557 -0.0394882 -0.021483 -0.10905 -0.0434779 -0.021483 -0.107355 -0.0475087 -0.021483 -0.0959339 -0.0567195 -0.0126994 -0.0974207 -0.0575986 -0.0155526 -0.0981274 -0.0528339 -0.0126994 -0.103367 -0.0556549 -0.021483 -0.101056 -0.059748 -0.021483 -0.078153 -0.0794514 -0.0126994 -0.0816895 -0.0758106 -0.0126994 -0.0860513 -0.0798584 -0.021483 -0.0823259 -0.0836937 -0.021483 -0.066147 -0.0896939 -0.0126994 -0.0671721 -0.091084 -0.0155526 -0.0703795 -0.0864126 -0.0126994 -0.0741374 -0.0910265 -0.021483 -0.0626461 -0.0942542 -0.0155526 -0.0578997 -0.097242 -0.0155526 -0.0589176 -0.0989515 -0.0185002 -0.0470575 -0.101025 -0.0126994 -0.0477868 -0.10259 -0.0155526 -0.0521346 -0.0985007 -0.0126994 -0.0549184 -0.10376 -0.021483 -0.0254931 -0.110266 -0.0155526 -0.0259413 -0.112204 -0.0185002 -0.0195993 -0.111464 -0.0155526 -0.0199439 -0.113424 -0.0185002 -0.0136223 -0.112351 -0.0155526 -0.0138618 -0.114326 -0.0185002 -0.00149586 -0.111437 -0.0126994 -0.00151905 -0.113164 -0.0155526 -0.00747125 -0.111196 -0.0126994 -0.00787017 -0.117133 -0.021483 0.0284014 -0.109552 -0.0155526 0.0341265 -0.107906 -0.0155526 0.0347264 -0.109803 -0.0185002 0.0397121 -0.105978 -0.0155526 0.0404102 -0.107841 -0.0185002 0.0496197 -0.0997913 -0.0126994 0.0503887 -0.101338 -0.0155526 0.0444498 -0.102199 -0.0126994 0.0468232 -0.107656 -0.021483 0.0602999 -0.0957721 -0.0155526 0.0649372 -0.0926906 -0.0155526 0.0660788 -0.09432 -0.0185002 0.0673605 -0.0961496 -0.021483 0.0803708 -0.0855729 -0.021483 0.0895148 -0.0663891 -0.0126994 0.0909021 -0.067418 -0.0155526 0.0865573 -0.0702015 -0.0126994 0.091179 -0.0739499 -0.021483 0.0942944 -0.0699339 -0.021483 0.0971723 -0.0658767 -0.021483 0.0998182 -0.0617941 -0.021483 0.102239 -0.0577011 -0.021483 0.104442 -0.0536111 -0.021483 0.106435 -0.0495366 -0.021483 0.108226 -0.0454887 -0.021483 0.109826 -0.0414774 -0.021483 0.111243 -0.0375114 -0.021483 0.112487 -0.0335985 -0.021483 0.113567 -0.0297454 -0.021483 0.114492 -0.0259578 -0.021483 0.115272 -0.0222404 -0.021483 0.116431 -0.0150319 -0.021483 0.116828 -0.0115463 -0.021483 0.117387 -0.00158638 -0.021483 0.117298 -0.00482252 -0.021483 0.115066 -0.00473076 -0.0185002 0.117115 -0.00814279 -0.021483 0.117387 0.00158638 -0.021483 0.117298 0.00482252 -0.021483 0.117115 0.00814279 -0.021483 0.115915 0.0185974 -0.021483 0.116431 0.0150319 -0.021483 0.114216 0.0147458 -0.0185002 0.116828 0.0115463 -0.021483 0.115272 0.0222404 -0.021483 0.114492 0.0259578 -0.021483 0.113567 0.0297454 -0.021483 0.112487 0.0335985 -0.021483 0.111243 0.0375114 -0.021483 0.109826 0.0414774 -0.021483 0.108226 0.0454887 -0.021483 0.102239 0.0577011 -0.021483 0.0998182 0.0617941 -0.021483 0.0971723 0.0658767 -0.021483 0.0942944 0.0699339 -0.021483 0.091179 0.0739499 -0.021483 0.0878216 0.0779073 -0.021483 0.0774795 0.0824943 -0.0155526 0.0735322 0.0860314 -0.0155526 0.0748249 0.0875438 -0.0185002 0.0762763 0.0892419 -0.021483 0.0554468 0.0986612 -0.0155526 0.0564216 0.100396 -0.0185002 0.057516 0.102343 -0.021483 0.0341265 0.107906 -0.0155526 0.0284014 0.109552 -0.0155526 0.0289007 0.111478 -0.0185002 0.0225581 0.110903 -0.0155526 0.0229547 0.112853 -0.0185002 0.0166197 0.111947 -0.0155526 0.0169119 0.113915 -0.0185002 0.0106104 0.112676 -0.0155526 0.0107969 0.114656 -0.0185002 0.0110064 0.11688 -0.021483 -0.0254931 0.110266 -0.0155526 -0.0312801 0.108766 -0.0155526 -0.03183 0.110678 -0.0185002 -0.036938 0.106976 -0.0155526 -0.0375874 0.108857 -0.0185002 -0.0424464 0.104913 -0.0155526 -0.0431926 0.106757 -0.0185002 -0.0440305 0.108828 -0.021483 -0.0703795 0.0864126 -0.0126994 -0.0714703 0.0877518 -0.0155526 -0.066147 0.0896939 -0.0126994 -0.0696789 0.094483 -0.021483 -0.0816895 0.0758106 -0.0126994 -0.078153 0.0794514 -0.0126994 -0.0823259 0.0836937 -0.021483 -0.0860513 0.0798584 -0.021483 -0.0895308 0.075937 -0.021483 -0.103367 0.0556549 -0.021483 -0.105464 0.0515712 -0.021483 -0.107355 0.0475087 -0.021483 -0.10905 0.0434779 -0.021483 -0.110557 0.0394882 -0.021483 -0.111886 0.0355479 -0.021483 -0.11561 0.0204094 -0.021483 -0.114899 0.02409 -0.021483 -0.112713 0.0236317 -0.0185002 -0.114048 0.0278431 -0.021483 -0.116189 0.0168048 -0.021483 -0.114425 0.0130263 -0.0185002 -0.117354 0.0031939 -0.021483 -0.117219 0.00647218 -0.021483 -0.114989 -0.00634903 -0.0185002 -0.113978 -0.016485 -0.0185002 -0.11341 -0.0200211 -0.0185002 -0.112713 -0.0236317 -0.0185002 -0.103827 -0.0363304 -0.01 -0.104953 -0.0374866 -0.0126994 -0.106215 -0.033746 -0.0126994 -0.110896 -0.0310616 -0.0185002 -0.109757 -0.0348715 -0.0185002 -0.108453 -0.0387368 -0.0185002 -0.106975 -0.0426506 -0.0185002 -0.105312 -0.0466047 -0.0185002 -0.103457 -0.0505899 -0.0185002 -0.1014 -0.0545959 -0.0185002 -0.0991333 -0.0586111 -0.0185002 -0.0880645 -0.0683012 -0.0126994 -0.0878913 -0.0661447 -0.01 -0.0860017 -0.0685836 -0.01 -0.0939405 -0.0666173 -0.0185002 -0.0849926 -0.0720879 -0.0126994 -0.0863099 -0.0732051 -0.0155526 -0.0878271 -0.0744921 -0.0185002 -0.0844138 -0.0783388 -0.0185002 -0.0807594 -0.0821011 -0.0185002 -0.0727267 -0.0892944 -0.0185002 -0.06169 -0.0928157 -0.0126994 -0.0637474 -0.0959111 -0.0185002 -0.0538733 -0.101786 -0.0185002 -0.0417986 -0.103312 -0.0126994 -0.0424464 -0.104913 -0.0155526 -0.0363743 -0.105344 -0.0126994 -0.0375874 -0.108857 -0.0185002 -0.00772041 -0.114905 -0.0185002 0.00448598 -0.111357 -0.0126994 0.0045555 -0.113082 -0.0155526 0.0104485 -0.110956 -0.0126994 0.0106104 -0.112676 -0.0155526 0.0163661 -0.110239 -0.0126994 0.0166197 -0.111947 -0.0155526 0.0222138 -0.109211 -0.0126994 0.0225581 -0.110903 -0.0155526 0.0279679 -0.107881 -0.0126994 0.0289007 -0.111478 -0.0185002 0.0459322 -0.105607 -0.0185002 0.0546006 -0.0971555 -0.0126994 0.0554468 -0.0986612 -0.0155526 0.0593797 -0.0943105 -0.0126994 0.06136 -0.0974558 -0.0185002 0.0682917 -0.0880719 -0.0126994 0.07241 -0.0847184 -0.0126994 0.0748249 -0.0875438 -0.0185002 0.0799505 -0.0776423 -0.0126994 0.0833701 -0.0739583 -0.0126994 0.0846622 -0.0751045 -0.0155526 0.0861505 -0.0764248 -0.0185002 0.089444 -0.0725427 -0.0185002 0.0925001 -0.0686032 -0.0185002 0.0953232 -0.0646232 -0.0185002 0.0979188 -0.0606183 -0.0185002 0.100293 -0.0566031 -0.0185002 0.102454 -0.052591 -0.0185002 0.104409 -0.048594 -0.0185002 0.106167 -0.0446231 -0.0185002 0.107736 -0.0406881 -0.0185002 0.109127 -0.0367976 -0.0185002 0.110347 -0.0329592 -0.0185002 0.112313 -0.0254638 -0.0185002 0.113078 -0.0218172 -0.0185002 0.113709 -0.0182435 -0.0185002 0.114216 -0.0147458 -0.0185002 0.114605 -0.0113266 -0.0185002 0.114886 -0.00798785 -0.0185002 0.115153 -0.00155619 -0.0185002 0.115153 0.00155619 -0.0185002 0.115066 0.00473076 -0.0185002 0.114886 0.00798785 -0.0185002 0.114605 0.0113266 -0.0185002 0.113709 0.0182435 -0.0185002 0.106513 0.027475 -0.01 0.10781 0.0282377 -0.0126994 0.108688 0.024642 -0.0126994 0.113078 0.0218172 -0.0185002 0.112313 0.0254638 -0.0185002 0.111406 0.0291794 -0.0185002 0.110347 0.0329592 -0.0185002 0.109127 0.0367976 -0.0185002 0.106167 0.0446231 -0.0185002 0.0970565 0.0547763 -0.0126994 0.0991476 0.0508937 -0.0126994 0.0962747 0.0532089 -0.01 0.102454 0.052591 -0.0185002 0.100293 0.0566031 -0.0185002 0.0979188 0.0606183 -0.0185002 0.0953232 0.0646232 -0.0185002 0.0925001 0.0686032 -0.0185002 0.089444 0.0725427 -0.0185002 0.0799505 0.0776423 -0.0126994 0.076297 0.0812353 -0.0126994 0.0788415 0.0839446 -0.0185002 0.0682917 0.0880719 -0.0126994 0.0639461 0.091276 -0.0126994 0.0660788 0.09432 -0.0185002 0.0496197 0.0997913 -0.0126994 0.0444498 0.102199 -0.0126994 0.0451387 0.103783 -0.0155526 0.0391061 0.104361 -0.0126994 0.0397121 0.105978 -0.0155526 0.0336057 0.106259 -0.0126994 0.0347264 0.109803 -0.0185002 0.00448598 0.111357 -0.0126994 -0.00149586 0.111437 -0.0126994 -0.00151905 0.113164 -0.0155526 -0.00747125 0.111196 -0.0126994 -0.00758704 0.11292 -0.0155526 -0.0134144 0.110637 -0.0126994 -0.0136223 0.112351 -0.0155526 -0.0193002 0.109763 -0.0126994 -0.0195993 0.111464 -0.0155526 -0.025104 0.108583 -0.0126994 -0.0259413 0.112204 -0.0185002 -0.0470575 0.101025 -0.0126994 -0.0521346 0.0985007 -0.0126994 -0.0529426 0.100027 -0.0155526 -0.0570161 0.0957579 -0.0126994 -0.0589176 0.0989515 -0.0185002 -0.068353 0.0926852 -0.0185002 -0.0743826 0.0829918 -0.0126994 -0.0755354 0.084278 -0.0155526 -0.0768633 0.0857596 -0.0185002 -0.0807594 0.0821011 -0.0185002 -0.0844138 0.0783388 -0.0185002 -0.0880645 0.0683012 -0.0126994 -0.0909087 0.0644673 -0.0126994 -0.0923176 0.0654664 -0.0155526 -0.0939405 0.0666173 -0.0185002 -0.0981274 0.0528339 -0.0126994 -0.0959339 0.0567195 -0.0126994 -0.0962744 0.0532093 -0.01 -0.0991333 0.0586111 -0.0185002 -0.1014 0.0545959 -0.0185002 -0.103457 0.0505899 -0.0185002 -0.105312 0.0466047 -0.0185002 -0.106975 0.0426506 -0.0185002 -0.108453 0.0387368 -0.0185002 -0.109757 0.0348715 -0.0185002 -0.110896 0.0310616 -0.0185002 -0.111878 0.0273133 -0.0185002 -0.111451 0.0196752 -0.0155526 -0.112009 0.0162002 -0.0155526 -0.113978 0.016485 -0.0185002 -0.11341 0.0200211 -0.0185002 -0.114989 0.00634903 -0.0185002 -0.110732 -0.0126059 -0.0126994 -0.112448 -0.0128012 -0.0155526 -0.111055 -0.00933575 -0.0126994 -0.112009 -0.0162002 -0.0155526 -0.111451 -0.0196752 -0.0155526 -0.110766 -0.0232234 -0.0155526 -0.109945 -0.0268414 -0.0155526 -0.10898 -0.030525 -0.0155526 -0.107861 -0.034269 -0.0155526 -0.10658 -0.0380676 -0.0155526 -0.105127 -0.0419138 -0.0155526 -0.103493 -0.0457995 -0.0155526 -0.0996482 -0.0536527 -0.0155526 -0.0949794 -0.061541 -0.0155526 -0.0923176 -0.0654664 -0.0155526 -0.0894293 -0.0693597 -0.0155526 -0.0829555 -0.0769855 -0.0155526 -0.0685842 -0.0860012 -0.01 -0.0709692 -0.0840439 -0.01 -0.0714703 -0.0877518 -0.0155526 -0.0504884 -0.0977288 -0.01 -0.0532093 -0.0962744 -0.01 -0.0529426 -0.100027 -0.0155526 -0.0308027 -0.107106 -0.0126994 -0.0184261 -0.108446 -0.01 -0.0193002 -0.109763 -0.0126994 -0.0214601 -0.107886 -0.01 -0.0123162 -0.109308 -0.01 -0.0134144 -0.110637 -0.0126994 -0.0153772 -0.10892 -0.01 -0.00616814 -0.109827 -0.01 -0.00924585 -0.109611 -0.01 -0.00758704 -0.11292 -0.0155526 0.039228 -0.102768 -0.01 0.0391061 -0.104361 -0.0126994 0.0363304 -0.103827 -0.01 0.0449288 -0.100406 -0.01 0.042095 -0.101627 -0.01 0.0451387 -0.103783 -0.0155526 0.0685836 -0.0860017 -0.01 0.0661447 -0.0878913 -0.01 0.0693501 -0.0894369 -0.0155526 0.0799325 -0.0755698 -0.01 0.0777815 -0.077782 -0.01 0.0811896 -0.0788457 -0.0155526 0.0878988 -0.0712895 -0.0155526 0.0936764 -0.0635068 -0.0155526 0.0985607 -0.0556253 -0.0155526 0.102606 -0.0477545 -0.0155526 0.104333 -0.0438522 -0.0155526 0.107241 -0.0361619 -0.0155526 0.108688 -0.024642 -0.0126994 0.110373 -0.0250239 -0.0155526 0.10781 -0.0282377 -0.0126994 0.111125 -0.0214403 -0.0155526 0.111745 -0.0179283 -0.0155526 0.112243 -0.0144911 -0.0155526 0.112625 -0.011131 -0.0155526 0.112902 -0.00784985 -0.0155526 0.113079 -0.00464903 -0.0155526 0.113164 -0.00152931 -0.0155526 0.113164 0.00152931 -0.0155526 0.113079 0.00464903 -0.0155526 0.112902 0.00784985 -0.0155526 0.112625 0.011131 -0.0155526 0.112243 0.0144911 -0.0155526 0.111745 0.0179283 -0.0155526 0.111125 0.0214403 -0.0155526 0.110373 0.0250239 -0.0155526 0.109481 0.0286753 -0.0155526 0.10844 0.0323898 -0.0155526 0.102741 0.043183 -0.0126994 0.104333 0.0438522 -0.0155526 0.104259 0.039375 -0.0126994 0.102606 0.0477545 -0.0155526 0.100684 0.0516824 -0.0155526 0.0985607 0.0556253 -0.0155526 0.0962272 0.0595711 -0.0155526 0.0909021 0.067418 -0.0155526 0.077782 0.0777815 -0.01 0.0799329 0.0755694 -0.01 0.0811896 0.0788457 -0.0155526 0.066145 0.087891 -0.01 0.0685842 0.0860012 -0.01 0.0693501 0.0894369 -0.0155526 0.0532093 0.0962744 -0.01 0.0546006 0.0971555 -0.0126994 0.0558884 0.0947443 -0.01 0.0477275 0.0991065 -0.01 0.0504884 0.0977288 -0.01 0.0503887 0.101338 -0.0155526 0.0214601 0.107886 -0.01 0.0222138 0.109211 -0.0126994 0.0244774 0.107242 -0.01 0.0153772 0.10892 -0.01 0.0163661 0.110239 -0.0126994 0.0184261 0.108446 -0.01 0.00924585 0.109611 -0.01 0.0104485 0.110956 -0.0126994 0.0123162 0.109308 -0.01 0.00308534 0.109957 -0.01 0.00616814 0.109827 -0.01 0.0045555 0.113082 -0.0155526 -0.0363304 0.103827 -0.01 -0.0363743 0.105344 -0.0126994 -0.0334044 0.104805 -0.01 -0.042095 0.101627 -0.01 -0.0417986 0.103312 -0.0126994 -0.039228 0.102768 -0.01 -0.0477269 0.0991067 -0.01 -0.0449288 0.100406 -0.01 -0.0477868 0.10259 -0.0155526 -0.0661447 0.0878913 -0.01 -0.0636538 0.0897118 -0.01 -0.0671721 0.091084 -0.0155526 -0.0793642 0.0806827 -0.0155526 -0.087891 0.066145 -0.01 -0.0860012 0.0685842 -0.01 -0.0894293 0.0693597 -0.0155526 -0.0949794 0.061541 -0.0155526 -0.0974207 0.0575986 -0.0155526 -0.0996482 0.0536527 -0.0155526 -0.10167 0.0497159 -0.0155526 -0.105127 0.0419138 -0.0155526 -0.10658 0.0380676 -0.0155526 -0.10898 0.030525 -0.0155526 -0.109945 0.0268414 -0.0155526 -0.110766 0.0232234 -0.0155526 -0.113002 0.00623934 -0.0155526 -0.111055 0.00933575 -0.0126994 -0.109308 -0.012316 -0.01 -0.110299 -0.015953 -0.0126994 -0.10975 -0.0193749 -0.0126994 -0.109075 -0.022869 -0.0126994 -0.108267 -0.0264318 -0.0126994 -0.107317 -0.0300591 -0.0126994 -0.103522 -0.0412741 -0.0126994 -0.0991067 -0.0477269 -0.01 -0.0962747 -0.0532089 -0.01 -0.0935298 -0.0606018 -0.0126994 -0.0909087 -0.0644673 -0.0126994 -0.0799329 -0.0755694 -0.01 -0.0743826 -0.0829918 -0.0126994 -0.063654 -0.0897116 -0.01 -0.0570161 -0.0957579 -0.0126994 -0.0477275 -0.0991065 -0.01 -0.0449289 -0.100406 -0.01 -0.0392287 -0.102767 -0.01 -0.0334045 -0.104805 -0.01 -0.025104 -0.108583 -0.0126994 2.80664e-16 -0.11 -0.01 -0.00308534 -0.109957 -0.01 0.00616737 -0.109827 -0.01 0.012316 -0.109308 -0.01 0.0184253 -0.108446 -0.01 0.0244771 -0.107242 -0.01 0.0336057 -0.106259 -0.0126994 0.0477269 -0.0991067 -0.01 0.0504877 -0.0977292 -0.01 0.0558881 -0.0947445 -0.01 0.0639461 -0.091276 -0.0126994 0.076297 -0.0812353 -0.0126994 0.0860012 -0.0685842 -0.01 0.0914614 -0.061113 -0.01 0.0962744 -0.0532093 -0.01 0.10104 -0.0470257 -0.0126994 0.101627 -0.0420955 -0.01 0.105605 -0.03561 -0.0126994 0.106785 -0.0318955 -0.0126994 0.106513 -0.0274758 -0.01 0.109429 -0.0211131 -0.0126994 0.11004 -0.0176547 -0.0126994 0.11053 -0.0142699 -0.0126994 0.110907 -0.0109611 -0.0126994 0.111179 -0.00773005 -0.0126994 0.111353 -0.00457808 -0.0126994 0.111437 -0.00150597 -0.0126994 0.111437 0.00150597 -0.0126994 0.111353 0.00457808 -0.0126994 0.111179 0.00773005 -0.0126994 0.110907 0.0109611 -0.0126994 0.11053 0.0142699 -0.0126994 0.11004 0.0176547 -0.0126994 0.109429 0.0211131 -0.0126994 0.106785 0.0318955 -0.0126994 0.105605 0.03561 -0.0126994 0.101627 0.042095 -0.01 0.10104 0.0470257 -0.0126994 0.0931399 0.0585232 -0.01 0.0860017 0.0685836 -0.01 0.0833701 0.0739583 -0.0126994 0.07241 0.0847184 -0.0126994 0.0593797 0.0943105 -0.0126994 0.0420955 0.101627 -0.01 0.0363309 0.103827 -0.01 0.0279679 0.107881 -0.0126994 -3.18856e-16 0.11 -0.01 -0.00308474 0.109957 -0.01 -0.00924536 0.109611 -0.01 -0.0153766 0.10892 -0.01 -0.0214598 0.107886 -0.01 -0.0308027 0.107106 -0.0126994 -0.0532089 0.0962747 -0.01 -0.06169 0.0928157 -0.0126994 -0.0709687 0.0840443 -0.01 -0.0799325 0.0755698 -0.01 -0.0849926 0.0720879 -0.0126994 -0.0935298 0.0606018 -0.0126994 -0.0991065 0.0477275 -0.01 -0.103522 0.0412741 -0.0126994 -0.103827 0.0363309 -0.01 -0.107317 0.0300591 -0.0126994 -0.108267 0.0264318 -0.0126994 -0.109075 0.022869 -0.0126994 -0.10975 0.0193749 -0.0126994 -0.110299 0.015953 -0.0126994 -0.110732 0.0126059 -0.0126994 -0.109308 0.0123162 -0.01 -0.109611 -0.00924536 -0.01 -0.10892 -0.0153766 -0.01 -0.108446 -0.0184253 -0.01 -0.107886 -0.0214598 -0.01 -0.107242 -0.0244771 -0.01 -0.106513 -0.027475 -0.01 -0.105701 -0.0304516 -0.01 -0.104805 -0.0334044 -0.01 -0.102768 -0.039228 -0.01 -0.101627 -0.042095 -0.01 -0.100406 -0.0449288 -0.01 -0.0977292 -0.0504877 -0.01 -0.0947445 -0.0558881 -0.01 -0.0931399 -0.0585232 -0.01 -0.0914618 -0.0611124 -0.01 -0.0897118 -0.0636538 -0.01 -0.0840443 -0.0709687 -0.01 -0.0820207 -0.0732981 -0.01 -0.077782 -0.0777815 -0.01 -0.0755698 -0.0799325 -0.01 -0.0732982 -0.0820206 -0.01 -0.066145 -0.087891 -0.01 -0.061113 -0.0914614 -0.01 -0.0585238 -0.0931395 -0.01 -0.0558884 -0.0947443 -0.01 -0.0420955 -0.101627 -0.01 -0.0363309 -0.103827 -0.01 -0.0304523 -0.105701 -0.01 -0.0274758 -0.106513 -0.01 -0.0244774 -0.107242 -0.01 0.00308474 -0.109957 -0.01 0.00924536 -0.109611 -0.01 0.0153766 -0.10892 -0.01 0.0214598 -0.107886 -0.01 0.027475 -0.106513 -0.01 0.0304516 -0.105701 -0.01 0.0334044 -0.104805 -0.01 0.0532089 -0.0962747 -0.01 0.0585232 -0.0931399 -0.01 0.0611124 -0.0914618 -0.01 0.0636538 -0.0897118 -0.01 0.0709687 -0.0840443 -0.01 0.0732981 -0.0820207 -0.01 0.0755694 -0.0799329 -0.01 0.0820206 -0.0732982 -0.01 0.0840439 -0.0709692 -0.01 0.087891 -0.066145 -0.01 0.0897116 -0.063654 -0.01 0.0931395 -0.0585238 -0.01 0.0947443 -0.0558884 -0.01 0.0977288 -0.0504884 -0.01 0.0991065 -0.0477275 -0.01 0.100406 -0.0449289 -0.01 0.102767 -0.0392287 -0.01 0.103827 -0.0363309 -0.01 0.104805 -0.0334045 -0.01 0.105701 -0.0304523 -0.01 0.107242 -0.0244774 -0.01 0.107886 -0.0214601 -0.01 0.108446 -0.0184261 -0.01 0.10892 -0.0153772 -0.01 0.109308 -0.0123162 -0.01 0.109611 -0.00924585 -0.01 0.109827 -0.00616814 -0.01 0.109957 -0.00308534 -0.01 0.11 8.80243e-14 -0.01 0.109957 0.00308534 -0.01 0.109827 0.00616737 -0.01 0.109611 0.00924536 -0.01 0.109308 0.012316 -0.01 0.10892 0.0153766 -0.01 0.108446 0.0184253 -0.01 0.107886 0.0214598 -0.01 0.107242 0.0244771 -0.01 0.105701 0.0304516 -0.01 0.104805 0.0334044 -0.01 0.103827 0.0363304 -0.01 0.102768 0.039228 -0.01 0.100406 0.0449288 -0.01 0.0991067 0.0477269 -0.01 0.0977292 0.0504877 -0.01 0.0947445 0.0558881 -0.01 0.0914618 0.0611124 -0.01 0.0897118 0.0636538 -0.01 0.0878913 0.0661447 -0.01 0.0840443 0.0709687 -0.01 0.0820207 0.0732981 -0.01 0.0755698 0.0799325 -0.01 0.0732982 0.0820206 -0.01 0.0709692 0.0840439 -0.01 0.063654 0.0897116 -0.01 0.061113 0.0914614 -0.01 0.0585238 0.0931395 -0.01 0.0449289 0.100406 -0.01 0.0392287 0.102767 -0.01 0.0334045 0.104805 -0.01 0.0304523 0.105701 -0.01 0.0274758 0.106513 -0.01 -0.00616737 0.109827 -0.01 -0.012316 0.109308 -0.01 -0.0184253 0.108446 -0.01 -0.0244771 0.107242 -0.01 -0.027475 0.106513 -0.01 -0.0304516 0.105701 -0.01 -0.0504877 0.0977292 -0.01 -0.0558881 0.0947445 -0.01 -0.0585232 0.0931399 -0.01 -0.0611124 0.0914618 -0.01 -0.0685836 0.0860017 -0.01 -0.0732981 0.0820207 -0.01 -0.0755694 0.0799329 -0.01 -0.0777815 0.077782 -0.01 -0.0820206 0.0732982 -0.01 -0.0840439 0.0709692 -0.01 -0.0897116 0.063654 -0.01 -0.0914614 0.061113 -0.01 -0.0931395 0.0585238 -0.01 -0.0947443 0.0558884 -0.01 -0.0977288 0.0504884 -0.01 -0.100406 0.0449289 -0.01 -0.101627 0.0420955 -0.01 -0.102767 0.0392287 -0.01 -0.104805 0.0334045 -0.01 -0.105701 0.0304523 -0.01 -0.106513 0.0274758 -0.01 -0.107242 0.0244774 -0.01 -0.107886 0.0214601 -0.01 -0.108446 0.0184261 -0.01 -0.10892 0.0153772 -0.01 -0.109611 0.00924585 -0.01 -0.109827 0.00616814 -0.01 -0.109957 0.00308534 -0.01 0.109827 -0.00616737 0.01 0.109957 -0.00308534 -0.01 0.109827 -0.00616814 -0.01 0.11 8.80243e-14 -0.01 0.109957 -0.00308534 0.01 0.11 2.45709e-15 0.01 0.109308 -0.0123162 -0.01 0.10892 -0.0153772 -0.01 0.10892 -0.0153766 0.01 0.109308 -0.012316 0.01 0.109611 -0.00924536 0.01 0.109611 -0.00924585 -0.01 0.107242 -0.0244771 0.01 0.107886 -0.0214601 -0.01 0.107242 -0.0244774 -0.01 0.107886 -0.0214598 0.01 0.108446 -0.0184253 0.01 0.108446 -0.0184261 -0.01 0.104805 -0.0334045 -0.01 0.104805 -0.0334044 0.01 0.105701 -0.0304523 -0.01 0.106513 -0.0274758 -0.01 0.105701 -0.0304516 0.01 0.106513 -0.027475 0.01 0.102767 -0.0392287 -0.01 0.101627 -0.0420955 -0.01 0.101627 -0.042095 0.01 0.103827 -0.0363304 0.01 0.103827 -0.0363309 -0.01 0.102768 -0.039228 0.01 0.0977292 -0.0504877 0.01 0.0991065 -0.0477275 -0.01 0.0977288 -0.0504884 -0.01 0.0991067 -0.0477269 0.01 0.100406 -0.0449288 0.01 0.100406 -0.0449289 -0.01 0.0931395 -0.0585238 -0.01 0.0931399 -0.0585232 0.01 0.0947443 -0.0558884 -0.01 0.0962744 -0.0532093 -0.01 0.0947445 -0.0558881 0.01 0.0962747 -0.0532089 0.01 0.0897116 -0.063654 -0.01 0.087891 -0.066145 -0.01 0.0878913 -0.0661447 0.01 0.0914618 -0.0611124 0.01 0.0914614 -0.061113 -0.01 0.0897118 -0.0636538 0.01 0.0820207 -0.0732981 0.01 0.0840439 -0.0709692 -0.01 0.0820206 -0.0732982 -0.01 0.0840443 -0.0709687 0.01 0.0860017 -0.0685836 0.01 0.0860012 -0.0685842 -0.01 0.0755694 -0.0799329 -0.01 0.0755698 -0.0799325 0.01 0.0777815 -0.077782 -0.01 0.0799325 -0.0755698 -0.01 0.077782 -0.0777815 0.01 0.0799329 -0.0755694 0.01 0.0709687 -0.0840443 -0.01 0.0685836 -0.0860017 -0.01 0.0685842 -0.0860012 0.01 0.0732982 -0.0820206 0.01 0.0732981 -0.0820207 -0.01 0.0709692 -0.0840439 0.01 0.061113 -0.0914614 0.01 0.0636538 -0.0897118 -0.01 0.0611124 -0.0914618 -0.01 0.063654 -0.0897116 0.01 0.066145 -0.087891 0.01 0.0661447 -0.0878913 -0.01 0.0532089 -0.0962747 -0.01 0.0532093 -0.0962744 0.01 0.0558881 -0.0947445 -0.01 0.0585232 -0.0931399 -0.01 0.0558884 -0.0947443 0.01 0.0585238 -0.0931395 0.01 0.0477269 -0.0991067 -0.01 0.0449288 -0.100406 -0.01 0.0449289 -0.100406 0.01 0.0504884 -0.0977288 0.01 0.0504877 -0.0977292 -0.01 0.0477275 -0.0991065 0.01 0.0363309 -0.103827 0.01 0.039228 -0.102768 -0.01 0.0363304 -0.103827 -0.01 0.0392287 -0.102767 0.01 0.0420955 -0.101627 0.01 0.042095 -0.101627 -0.01 0.027475 -0.106513 -0.01 0.0274758 -0.106513 0.01 0.0304516 -0.105701 -0.01 0.0334044 -0.104805 -0.01 0.0304523 -0.105701 0.01 0.0334045 -0.104805 0.01 0.0214598 -0.107886 -0.01 0.0184253 -0.108446 -0.01 0.0184261 -0.108446 0.01 0.0244774 -0.107242 0.01 0.0244771 -0.107242 -0.01 0.0214601 -0.107886 0.01 0.00924585 -0.109611 0.01 0.012316 -0.109308 -0.01 0.00924536 -0.109611 -0.01 0.0123162 -0.109308 0.01 0.0153772 -0.10892 0.01 0.0153766 -0.10892 -0.01 2.80664e-16 -0.11 -0.01 -3.20632e-16 -0.11 0.01 0.00308474 -0.109957 -0.01 0.00616737 -0.109827 -0.01 0.00308534 -0.109957 0.01 0.00616814 -0.109827 0.01 -0.00616814 -0.109827 -0.01 -0.00924585 -0.109611 -0.01 -0.00924536 -0.109611 0.01 -0.00308474 -0.109957 0.01 -0.00308534 -0.109957 -0.01 -0.00616737 -0.109827 0.01 -0.0184253 -0.108446 0.01 -0.0153772 -0.10892 -0.01 -0.0184261 -0.108446 -0.01 -0.0153766 -0.10892 0.01 -0.012316 -0.109308 0.01 -0.0123162 -0.109308 -0.01 -0.0274758 -0.106513 -0.01 -0.027475 -0.106513 0.01 -0.0244774 -0.107242 -0.01 -0.0214601 -0.107886 -0.01 -0.0244771 -0.107242 0.01 -0.0214598 -0.107886 0.01 -0.0334045 -0.104805 -0.01 -0.0363309 -0.103827 -0.01 -0.0363304 -0.103827 0.01 -0.0304516 -0.105701 0.01 -0.0304523 -0.105701 -0.01 -0.0334044 -0.104805 0.01 -0.0449288 -0.100406 0.01 -0.0420955 -0.101627 -0.01 -0.0449289 -0.100406 -0.01 -0.042095 -0.101627 0.01 -0.039228 -0.102768 0.01 -0.0392287 -0.102767 -0.01 -0.0532093 -0.0962744 -0.01 -0.0532089 -0.0962747 0.01 -0.0504884 -0.0977288 -0.01 -0.0477275 -0.0991065 -0.01 -0.0504877 -0.0977292 0.01 -0.0477269 -0.0991067 0.01 -0.0585238 -0.0931395 -0.01 -0.061113 -0.0914614 -0.01 -0.0611124 -0.0914618 0.01 -0.0558881 -0.0947445 0.01 -0.0558884 -0.0947443 -0.01 -0.0585232 -0.0931399 0.01 -0.0685836 -0.0860017 0.01 -0.066145 -0.087891 -0.01 -0.0685842 -0.0860012 -0.01 -0.0661447 -0.0878913 0.01 -0.0636538 -0.0897118 0.01 -0.063654 -0.0897116 -0.01 -0.0755698 -0.0799325 -0.01 -0.0755694 -0.0799329 0.01 -0.0732982 -0.0820206 -0.01 -0.0709692 -0.0840439 -0.01 -0.0732981 -0.0820207 0.01 -0.0709687 -0.0840443 0.01 -0.0799329 -0.0755694 -0.01 -0.0820207 -0.0732981 -0.01 -0.0820206 -0.0732982 0.01 -0.0777815 -0.077782 0.01 -0.077782 -0.0777815 -0.01 -0.0799325 -0.0755698 0.01 -0.087891 -0.066145 0.01 -0.0860017 -0.0685836 -0.01 -0.0878913 -0.0661447 -0.01 -0.0860012 -0.0685842 0.01 -0.0840439 -0.0709692 0.01 -0.0840443 -0.0709687 -0.01 -0.0931399 -0.0585232 -0.01 -0.0931395 -0.0585238 0.01 -0.0914618 -0.0611124 -0.01 -0.0897118 -0.0636538 -0.01 -0.0914614 -0.061113 0.01 -0.0897116 -0.063654 0.01 -0.0962747 -0.0532089 -0.01 -0.0977292 -0.0504877 -0.01 -0.0977288 -0.0504884 0.01 -0.0947443 -0.0558884 0.01 -0.0947445 -0.0558881 -0.01 -0.0962744 -0.0532093 0.01 -0.101627 -0.0420955 0.01 -0.100406 -0.0449288 -0.01 -0.101627 -0.042095 -0.01 -0.100406 -0.0449289 0.01 -0.0991065 -0.0477275 0.01 -0.0991067 -0.0477269 -0.01 -0.104805 -0.0334044 -0.01 -0.104805 -0.0334045 0.01 -0.103827 -0.0363304 -0.01 -0.102768 -0.039228 -0.01 -0.103827 -0.0363309 0.01 -0.102767 -0.0392287 0.01 -0.106513 -0.027475 -0.01 -0.107242 -0.0244771 -0.01 -0.107242 -0.0244774 0.01 -0.105701 -0.0304523 0.01 -0.105701 -0.0304516 -0.01 -0.106513 -0.0274758 0.01 -0.10892 -0.0153772 0.01 -0.108446 -0.0184253 -0.01 -0.10892 -0.0153766 -0.01 -0.108446 -0.0184261 0.01 -0.107886 -0.0214601 0.01 -0.107886 -0.0214598 -0.01 -0.109827 -0.00616737 -0.01 -0.109827 -0.00616814 0.01 -0.109611 -0.00924536 -0.01 -0.109308 -0.012316 -0.01 -0.109611 -0.00924585 0.01 -0.109308 -0.0123162 0.01 -0.11 0 -0.01 -0.109957 0.00308534 -0.01 -0.109957 0.00308534 0.01 -0.109957 -0.00308534 0.01 -0.109957 -0.00308534 -0.01 -0.11 0 0.01 -0.109308 0.012316 0.01 -0.109611 0.00924585 -0.01 -0.109308 0.0123162 -0.01 -0.109611 0.00924536 0.01 -0.109827 0.00616737 0.01 -0.109827 0.00616814 -0.01 -0.107886 0.0214601 -0.01 -0.107886 0.0214598 0.01 -0.108446 0.0184261 -0.01 -0.10892 0.0153772 -0.01 -0.108446 0.0184253 0.01 -0.10892 0.0153766 0.01 -0.106513 0.0274758 -0.01 -0.105701 0.0304523 -0.01 -0.105701 0.0304516 0.01 -0.107242 0.0244771 0.01 -0.107242 0.0244774 -0.01 -0.106513 0.027475 0.01 -0.102768 0.039228 0.01 -0.103827 0.0363309 -0.01 -0.102767 0.0392287 -0.01 -0.103827 0.0363304 0.01 -0.104805 0.0334044 0.01 -0.104805 0.0334045 -0.01 -0.0991065 0.0477275 -0.01 -0.0991067 0.0477269 0.01 -0.100406 0.0449289 -0.01 -0.101627 0.0420955 -0.01 -0.100406 0.0449288 0.01 -0.101627 0.042095 0.01 -0.0962744 0.0532093 -0.01 -0.0947443 0.0558884 -0.01 -0.0947445 0.0558881 0.01 -0.0977292 0.0504877 0.01 -0.0977288 0.0504884 -0.01 -0.0962747 0.0532089 0.01 -0.0897118 0.0636538 0.01 -0.0914614 0.061113 -0.01 -0.0897116 0.063654 -0.01 -0.0914618 0.0611124 0.01 -0.0931399 0.0585232 0.01 -0.0931395 0.0585238 -0.01 -0.0840439 0.0709692 -0.01 -0.0840443 0.0709687 0.01 -0.0860012 0.0685842 -0.01 -0.087891 0.066145 -0.01 -0.0860017 0.0685836 0.01 -0.0878913 0.0661447 0.01 -0.0799325 0.0755698 -0.01 -0.0777815 0.077782 -0.01 -0.077782 0.0777815 0.01 -0.0820207 0.0732981 0.01 -0.0820206 0.0732982 -0.01 -0.0799329 0.0755694 0.01 -0.0709692 0.0840439 0.01 -0.0732981 0.0820207 -0.01 -0.0709687 0.0840443 -0.01 -0.0732982 0.0820206 0.01 -0.0755698 0.0799325 0.01 -0.0755694 0.0799329 -0.01 -0.0636538 0.0897118 -0.01 -0.063654 0.0897116 0.01 -0.0661447 0.0878913 -0.01 -0.0685836 0.0860017 -0.01 -0.066145 0.087891 0.01 -0.0685842 0.0860012 0.01 -0.0585232 0.0931399 -0.01 -0.0558881 0.0947445 -0.01 -0.0558884 0.0947443 0.01 -0.061113 0.0914614 0.01 -0.0611124 0.0914618 -0.01 -0.0585238 0.0931395 0.01 -0.0477275 0.0991065 0.01 -0.0504877 0.0977292 -0.01 -0.0477269 0.0991067 -0.01 -0.0504884 0.0977288 0.01 -0.0532093 0.0962744 0.01 -0.0532089 0.0962747 -0.01 -0.039228 0.102768 -0.01 -0.0392287 0.102767 0.01 -0.042095 0.101627 -0.01 -0.0449288 0.100406 -0.01 -0.0420955 0.101627 0.01 -0.0449289 0.100406 0.01 -0.0334044 0.104805 -0.01 -0.0304516 0.105701 -0.01 -0.0304523 0.105701 0.01 -0.0363309 0.103827 0.01 -0.0363304 0.103827 -0.01 -0.0334045 0.104805 0.01 -0.0214601 0.107886 0.01 -0.0244771 0.107242 -0.01 -0.0214598 0.107886 -0.01 -0.0244774 0.107242 0.01 -0.0274758 0.106513 0.01 -0.027475 0.106513 -0.01 -0.012316 0.109308 -0.01 -0.0123162 0.109308 0.01 -0.0153766 0.10892 -0.01 -0.0184253 0.108446 -0.01 -0.0153772 0.10892 0.01 -0.0184261 0.108446 0.01 -0.00616737 0.109827 -0.01 -0.00308474 0.109957 -0.01 -0.00308534 0.109957 0.01 -0.00924585 0.109611 0.01 -0.00924536 0.109611 -0.01 -0.00616814 0.109827 0.01 -3.18856e-16 0.11 -0.01 0.00308534 0.109957 -0.01 0.00308474 0.109957 0.01 3.08198e-16 0.11 0.01 0.00616814 0.109827 -0.01 0.00616737 0.109827 0.01 0.00924536 0.109611 0.01 0.00924585 0.109611 -0.01 0.0123162 0.109308 -0.01 0.012316 0.109308 0.01 0.0153772 0.10892 -0.01 0.0153766 0.10892 0.01 0.0184253 0.108446 0.01 0.0184261 0.108446 -0.01 0.0214601 0.107886 -0.01 0.0214598 0.107886 0.01 0.0244774 0.107242 -0.01 0.0244771 0.107242 0.01 0.027475 0.106513 0.01 0.0274758 0.106513 -0.01 0.0304523 0.105701 -0.01 0.0304516 0.105701 0.01 0.0334045 0.104805 -0.01 0.0334044 0.104805 0.01 0.0363304 0.103827 0.01 0.0363309 0.103827 -0.01 0.0392287 0.102767 -0.01 0.039228 0.102768 0.01 0.0420955 0.101627 -0.01 0.042095 0.101627 0.01 0.0449288 0.100406 0.01 0.0449289 0.100406 -0.01 0.0477275 0.0991065 -0.01 0.0477269 0.0991067 0.01 0.0504884 0.0977288 -0.01 0.0504877 0.0977292 0.01 0.0532089 0.0962747 0.01 0.0532093 0.0962744 -0.01 0.0558884 0.0947443 -0.01 0.0558881 0.0947445 0.01 0.0585238 0.0931395 -0.01 0.0585232 0.0931399 0.01 0.0611124 0.0914618 0.01 0.061113 0.0914614 -0.01 0.063654 0.0897116 -0.01 0.0636538 0.0897118 0.01 0.066145 0.087891 -0.01 0.0661447 0.0878913 0.01 0.0685836 0.0860017 0.01 0.0685842 0.0860012 -0.01 0.0709692 0.0840439 -0.01 0.0709687 0.0840443 0.01 0.0732982 0.0820206 -0.01 0.0732981 0.0820207 0.01 0.0755694 0.0799329 0.01 0.0755698 0.0799325 -0.01 0.077782 0.0777815 -0.01 0.0777815 0.077782 0.01 0.0799329 0.0755694 -0.01 0.0799325 0.0755698 0.01 0.0820206 0.0732982 0.01 0.0820207 0.0732981 -0.01 0.0840443 0.0709687 -0.01 0.0840439 0.0709692 0.01 0.0860017 0.0685836 -0.01 0.0860012 0.0685842 0.01 0.087891 0.066145 0.01 0.0878913 0.0661447 -0.01 0.0897118 0.0636538 -0.01 0.0897116 0.063654 0.01 0.0914618 0.0611124 -0.01 0.0914614 0.061113 0.01 0.0931395 0.0585238 0.01 0.0931399 0.0585232 -0.01 0.0947445 0.0558881 -0.01 0.0947443 0.0558884 0.01 0.0962747 0.0532089 -0.01 0.0962744 0.0532093 0.01 0.0977288 0.0504884 0.01 0.0977292 0.0504877 -0.01 0.0991067 0.0477269 -0.01 0.0991065 0.0477275 0.01 0.100406 0.0449288 -0.01 0.100406 0.0449289 0.01 0.101627 0.0420955 0.01 0.101627 0.042095 -0.01 0.102768 0.039228 -0.01 0.102767 0.0392287 0.01 0.103827 0.0363304 -0.01 0.103827 0.0363309 0.01 0.104805 0.0334045 0.01 0.104805 0.0334044 -0.01 0.105701 0.0304516 -0.01 0.105701 0.0304523 0.01 0.106513 0.027475 -0.01 0.106513 0.0274758 0.01 0.107242 0.0244774 0.01 0.107242 0.0244771 -0.01 0.107886 0.0214598 -0.01 0.107886 0.0214601 0.01 0.108446 0.0184253 -0.01 0.108446 0.0184261 0.01 0.10892 0.0153772 0.01 0.10892 0.0153766 -0.01 0.109308 0.012316 -0.01 0.109308 0.0123162 0.01 0.109611 0.00924536 -0.01 0.109611 0.00924585 0.01 0.109827 0.00616814 0.01 0.109827 0.00616737 -0.01 0.109957 0.00308534 -0.01 0.109957 0.00308534 0.01 - - - - - - - - - - -0.564297 -0.660218 0.495662 -0.596058 -0.66699 0.447033 -0.594589 -0.633074 0.495662 0.794221 -0.351473 0.495662 0.806758 -0.321653 0.495662 0.826425 -0.342319 0.447033 0.537888 -0.714729 0.447033 0.515489 -0.698992 0.495662 0.557721 -0.699363 0.447033 0.49591 0.608882 0.619141 0.466086 0.632003 0.619141 0.483769 0.65598 0.57936 0.548474 -0.673421 0.495662 0.8165 -0.365361 0.447033 -0.866424 0.060241 0.495662 -0.89311 0.0501621 0.447033 -0.891352 0.0751876 0.447033 0.577116 -0.683446 0.447033 0.780228 -0.381527 0.495662 0.805931 -0.38812 0.447033 0.527188 -0.535946 0.65942 0.550683 -0.559832 0.619141 0.501754 -0.559829 0.65942 0.764716 -0.411739 0.495662 0.794728 -0.41057 0.447033 0.747621 -0.44202 0.495662 0.770458 -0.454483 0.447033 0.757408 -0.475914 0.447033 0.8357 -0.319008 0.447033 0.782902 -0.432696 0.447033 0.609053 -0.619172 0.495662 0.650009 -0.614532 0.447033 0.632518 -0.632521 0.447033 0.708459 -0.502399 0.495662 0.728886 -0.472275 0.495662 0.743762 -0.496969 0.447033 0.714727 -0.53789 0.447033 0.729533 -0.517632 0.447033 0.66699 -0.596059 0.447033 0.662355 -0.561787 0.495662 0.683443 -0.577119 0.447033 0.686295 -0.532277 0.495662 0.69936 -0.557725 0.447033 0.636614 -0.590798 0.495662 0.61453 -0.650011 0.447033 0.57967 -0.646763 0.495662 0.596058 -0.66699 0.447033 0.517631 -0.729534 0.447033 0.444331 -0.74625 0.495662 0.454482 -0.770459 0.447033 0.432694 -0.782903 0.447033 0.274953 -0.796293 0.538812 0.315956 -0.780931 0.538812 0.325741 -0.805116 0.495662 0.388116 -0.805933 0.447033 0.40629 -0.767625 0.495662 0.410566 -0.794731 0.447033 0.266025 -0.770437 0.57936 0.305696 -0.755574 0.57936 0.275047 -0.372958 0.886144 0.323763 -0.439016 0.838118 0.256514 -0.385939 0.886144 0.344157 -0.738849 0.57936 0.355707 -0.763645 0.538812 0.333574 -0.630239 0.70109 0.351679 -0.664445 0.65942 0.301089 -0.646389 0.70109 0.431041 -0.334307 0.838118 0.416006 -0.352842 0.838118 0.35341 -0.29975 0.886144 0.367352 -0.694058 0.619141 0.317431 -0.681472 0.65942 0.369411 -0.555798 0.744731 0.313311 -0.526202 0.790536 0.338995 -0.510034 0.790536 0.279071 -0.468697 0.838118 0.301948 -0.454296 0.838118 0.364807 -0.61269 0.70109 0.312192 -0.589841 0.744731 0.341423 -0.573416 0.744731 -0.176327 0.0949384 0.979743 -0.0501152 0.0269831 0.998379 -0.172386 0.101921 0.979743 0.286487 -0.541274 0.790536 0.23708 -0.398173 0.886144 0.294523 -0.727956 0.619141 0.331578 -0.711843 0.619141 0.200881 -0.302236 0.931826 0.215395 -0.29207 0.931826 0.229177 -0.281385 0.931826 0.143338 -0.194363 0.9704 0.15251 -0.187253 0.9704 -0.0213473 0.052763 0.998379 0.0418673 -0.0898822 0.995072 0.0371885 -0.0919168 0.995072 -0.0751089 0.185643 0.979743 -0.0845587 0.181534 0.979743 -0.0240331 0.0515951 0.998379 -0.388667 0.190056 0.901563 -0.462618 0.249083 0.850848 -0.472002 0.230806 0.850848 -0.216982 0.242096 0.945679 -0.140435 0.142768 0.979743 -0.13366 0.14913 0.979743 -0.0399139 0.0405771 0.998379 -0.0379883 0.0423852 0.998379 -0.596352 0.321088 0.735708 -0.533702 0.287356 0.795355 -0.583021 0.344703 0.735708 -0.0359439 0.0441322 0.998379 -0.126466 0.155276 0.979743 -0.28876 0.322182 0.901563 -0.22798 0.231768 0.945679 -0.806307 0.476718 0.350154 -0.824744 0.44406 0.350154 -0.789215 0.42493 0.443366 -0.462263 0.392076 0.795355 -0.516527 0.438101 0.735708 -0.478971 0.371481 0.795355 -0.303397 0.308438 0.901563 -0.368449 0.37457 0.850848 -0.317126 0.294303 0.901563 -0.496453 0.460725 0.735708 -0.444298 0.412323 0.795355 -0.630659 0.489127 0.602514 -0.604301 0.428536 0.671697 -0.585395 0.454022 0.671697 -0.535196 0.415088 0.735708 -0.564975 0.479193 0.671697 -0.637705 0.377034 0.671697 -0.669798 0.43399 0.602514 -0.687014 0.406187 0.602514 -0.671597 0.520878 0.52692 -0.651027 0.461671 0.602514 -0.238297 0.221147 0.945679 -0.693287 0.491639 0.52692 -0.731156 0.518495 0.443366 -0.713276 0.462161 0.52692 -0.708282 0.54933 0.443366 -0.679763 0.691056 0.245689 -0.695406 0.706959 0.128917 -0.710523 0.659389 0.245689 -0.860803 0.508938 1.91753e-07 -0.880486 0.474072 1.91753e-07 -0.873139 0.470116 0.128917 -0.841474 0.411476 -0.350154 -0.870812 0.425822 -0.245689 -0.824744 0.44406 -0.350154 -0.764072 0.541836 0.350155 -0.752238 0.487406 0.443366 -0.85362 0.504691 0.128917 -0.839232 0.543773 1.91753e-07 -0.85362 0.504691 -0.128917 -0.873139 0.470116 -0.128917 -0.832229 0.539235 -0.128917 -0.832229 0.539236 0.128917 -0.813509 0.527106 0.245689 -0.808906 0.57363 0.128917 -0.856565 0.379062 -0.350154 -0.805225 0.39375 -0.443366 -0.819665 0.362733 -0.443366 -0.789215 0.42493 -0.443366 -0.729836 0.32298 -0.602514 -0.777211 0.343945 -0.52692 -0.716978 0.350598 -0.602514 -0.832605 0.331957 -0.443366 -0.78948 0.314764 -0.52692 -0.533702 0.287356 -0.795355 -0.596352 0.321088 -0.735709 -0.521771 0.30849 -0.795355 -0.741357 0.295577 -0.602514 -0.500746 0.159094 -0.850848 -0.58368 0.163488 -0.795355 -0.577689 0.18354 -0.795355 -0.677454 0.299799 -0.671697 -0.688148 0.274363 -0.671697 -0.494797 0.176729 -0.850848 -0.570826 0.203885 -0.795355 -0.412336 0.131005 -0.901563 -0.505939 0.141713 -0.850848 -0.629138 0.250836 -0.735709 -0.563043 0.224484 -0.795355 -0.637834 0.227818 -0.735709 -0.0548082 0.0153517 -0.998379 -0.194548 0.0474958 -0.979743 -0.19284 0.0540139 -0.979743 -0.30984 0.0984407 -0.945679 -0.416613 0.116692 -0.901563 0.496966 -0.743765 0.447033 0.480756 -0.723321 0.495662 -0.197212 0.0348152 -0.979743 -0.0557064 0.0116795 -0.998379 -0.0560509 0.00989506 -0.998379 0.237824 -0.0419847 -0.9704 0.355182 -0.0744683 -0.931826 0.357378 -0.0630905 -0.931826 0.35255 -0.0860697 -0.931826 0.236362 -0.0495562 -0.9704 0.345868 -0.109887 -0.931826 0.232551 -0.0651371 -0.9704 0.230164 -0.0731265 -0.9704 -0.0552937 0.0134991 -0.998379 0.0963256 -0.0235164 -0.995072 0.606108 -0.0876637 -0.790536 0.603089 -0.106468 -0.790536 0.657203 -0.116021 -0.744731 0.456353 -0.0805632 -0.886144 0.453548 -0.095092 -0.886144 0.660492 -0.0955294 -0.744731 0.663082 -0.0754863 -0.744731 0.608485 -0.0692708 -0.790536 0.541988 -0.0617007 -0.838118 0.710567 -0.0597331 -0.70109 0.708497 -0.0806563 -0.70109 0.74695 -0.0850339 -0.65942 0.749133 -0.0629751 -0.65942 0.711988 -0.039312 -0.70109 -0.196 0.0410938 -0.979743 0.740327 -0.130695 -0.65942 0.744033 -0.107612 -0.65942 0.705729 -0.102072 -0.70109 0.868462 2.56167e-16 -0.495756 0.868194 -0.0236288 -0.495662 0.894517 4.15833e-16 -0.447033 0.844452 1.17246e-16 -0.535631 0.842114 -0.022919 -0.538812 0.867195 -0.0478817 -0.495662 0.81477 -0.0221748 -0.57936 0.820904 1.06052e-17 -0.571067 0.83702 -0.0952876 -0.538812 0.839465 -0.0705688 -0.538812 0.812207 -0.0682774 -0.57936 0.817909 -0.292137 0.495662 0.844319 -0.295444 0.447033 0.827743 -0.262986 0.495662 0.475911 -0.75741 0.447033 0.852274 -0.271644 0.447033 0.859556 -0.247638 0.447033 0.836328 -0.234254 0.495662 0.866163 -0.223434 0.447033 0.872089 -0.199052 0.447033 0.843735 -0.205985 0.495662 0.366723 -0.787295 0.495662 0.365361 -0.8165 0.447033 0.877329 -0.174513 0.447033 0.850034 -0.17822 0.495662 0.85529 -0.15099 0.495662 0.881878 -0.149841 0.447033 0.342316 -0.826427 0.447033 0.885733 -0.12505 0.447033 0.859572 -0.124323 0.495662 0.319003 -0.835702 0.447033 0.483926 -0.375324 0.790536 0.544378 -0.386042 0.744731 0.527347 -0.409 0.744731 0.283468 -0.820954 0.495662 0.384607 -0.645944 0.65942 0.232837 -0.80961 0.538812 0.824499 -0.172866 0.538812 0.29544 -0.84432 0.447033 0.888892 -0.100156 0.447033 0.862942 -0.0982386 0.495662 0.271644 -0.852274 0.447033 0.865463 -0.0727543 0.495662 0.891352 -0.0751875 0.447033 0.240048 -0.834683 0.495662 0.89311 -0.0501622 0.447033 0.189761 -0.820776 0.538812 0.223428 -0.866165 0.447033 0.247633 -0.859558 0.447033 0.195638 -0.846195 0.495662 0.867195 -0.0478817 0.495662 0.199049 -0.87209 0.447033 0.841145 -0.0464434 0.538812 0.868194 -0.0236288 0.495662 0.174511 -0.877329 0.447033 0.894166 -0.0250843 0.447033 0.894517 4.15833e-16 0.447033 0.150408 -0.855393 0.495662 0.1014 -0.836301 0.538812 0.14589 -0.829697 0.538812 0.125043 -0.885734 0.447033 0.149836 -0.881879 0.447033 0.10454 -0.862201 0.495662 0.0564748 -0.840531 0.538812 0.100154 -0.888893 0.447033 0.0751833 -0.891352 0.447033 0.0582238 -0.866562 0.495662 0.0113071 -0.84235 0.538812 0.0501541 -0.89311 0.447033 0.0250867 -0.894165 0.447033 0.0116573 -0.868437 0.495662 -0.0339094 -0.841743 0.538812 -6.66203e-08 -0.894517 0.447033 -0.0349596 -0.867812 0.495662 -0.0250893 -0.894165 0.447033 -0.07898 -0.838716 0.538812 -0.0814259 -0.86469 0.495662 -0.0501575 -0.89311 0.447033 -0.0751852 -0.891352 0.447033 -0.123711 -0.833293 0.538812 -0.100155 -0.888893 0.447033 -0.127542 -0.8591 0.495662 -0.167914 -0.825522 0.538812 -0.125046 -0.885734 0.447033 -0.149839 -0.881878 0.447033 -0.173114 -0.851088 0.495662 -0.211409 -0.815468 0.538812 -0.19905 -0.87209 0.447033 -0.174512 -0.877329 0.447033 -0.254025 -0.803214 0.538812 -0.217956 -0.840723 0.495662 -0.223431 -0.866164 0.447033 -0.247636 -0.859557 0.447033 -0.271644 -0.852274 0.447033 -0.261892 -0.828089 0.495662 -0.286004 -0.763246 0.57936 -0.245777 -0.777133 0.57936 -0.295442 -0.844319 0.447033 -0.304757 -0.813291 0.495662 -0.319006 -0.835701 0.447033 -0.335996 -0.772521 0.538812 -0.346401 -0.796446 0.495662 -0.375075 -0.754321 0.538812 -0.342318 -0.826426 0.447033 -0.365361 -0.8165 0.447033 -0.386691 -0.777682 0.495662 -0.412725 -0.734397 0.538812 -0.388118 -0.805932 0.447033 -0.410569 -0.794729 0.447033 -0.44885 -0.712892 0.538812 -0.425507 -0.757141 0.495662 -0.432696 -0.782902 0.447033 -0.454483 -0.770459 0.447033 -0.462751 -0.73497 0.495662 -0.483368 -0.689954 0.538812 -0.475914 -0.757408 0.447033 -0.496969 -0.743763 0.447033 -0.498338 -0.711322 0.495662 -0.517632 -0.729533 0.447033 -0.532203 -0.686352 0.495662 -0.53789 -0.714728 0.447033 -0.557724 -0.69936 0.447033 -0.499454 -0.644118 0.57936 -0.467673 -0.667551 0.57936 -0.577119 -0.683444 0.447033 -0.576728 -0.614057 0.538812 -0.547346 -0.640386 0.538812 -0.604345 -0.586898 0.538812 -0.614532 -0.650009 0.447033 -0.632521 -0.632518 0.447033 -0.623061 -0.605074 0.495662 -0.650011 -0.61453 0.447033 -0.649711 -0.576364 0.495662 -0.584721 -0.567841 0.57936 -0.609731 -0.540898 0.57936 -0.66699 -0.596058 0.447033 -0.683446 -0.577116 0.447033 -0.674549 -0.547086 0.495662 -0.676641 -0.501835 0.538812 -0.654286 -0.530652 0.538812 -0.699363 -0.557721 0.447033 -0.697597 -0.517376 0.495662 -0.714729 -0.537888 0.447033 -0.729534 -0.517631 0.447033 -0.718887 -0.48736 0.495662 -0.716279 -0.443425 0.538812 -0.697293 -0.472721 0.538812 -0.743765 -0.496965 0.447033 -0.738462 -0.457157 0.495662 -0.757411 -0.47591 0.447033 -0.770459 -0.454482 0.447033 -0.75637 -0.426877 0.495662 -0.709827 -0.400609 0.57936 -0.693021 -0.429027 0.57936 -0.782903 -0.432693 0.447033 -0.772666 -0.396619 0.495662 -0.794731 -0.410565 0.447033 -0.805933 -0.388114 0.447033 -0.78741 -0.366475 0.495662 -0.749456 -0.384705 0.538812 -0.738958 -0.343924 0.57936 -0.72512 -0.372213 0.57936 -0.8165 -0.36536 0.447033 -0.800667 -0.336529 0.495662 -0.826427 -0.342314 0.447033 -0.812503 -0.306853 0.495662 -0.835703 -0.319001 0.447033 -0.798264 -0.269176 0.538812 -0.788096 -0.297635 0.538812 -0.84432 -0.295439 0.447033 -0.822986 -0.277512 0.495662 -0.852274 -0.271643 0.447033 -0.832187 -0.248564 0.495662 -0.859558 -0.24763 0.447033 -0.866165 -0.223426 0.447033 -0.840175 -0.220059 0.495662 -0.814937 -0.213448 0.538812 -0.821575 -0.186269 0.538812 -0.847019 -0.192037 0.495662 -0.87209 -0.199047 0.447033 -0.87733 -0.174509 0.447033 -0.852788 -0.164536 0.495662 -0.881879 -0.149833 0.447033 -0.857549 -0.137585 0.495662 -0.885735 -0.125041 0.447033 -0.861367 -0.111207 0.495662 -0.888893 -0.100154 0.447033 -0.891352 -0.0751809 0.447033 -0.864305 -0.0854208 0.495662 -0.89311 -0.0501505 0.447033 -0.866424 -0.0602411 0.495662 -0.813109 -0.0565342 0.57936 -0.81112 -0.0801644 0.57936 -0.838342 -0.0828548 0.538812 -0.867783 -0.0356775 0.495662 -0.894165 -0.0250844 0.447033 -0.868436 -0.011736 0.495662 -0.894517 8.14756e-08 0.447033 -0.868436 0.0117362 0.495662 -0.894166 0.0250842 0.447033 -0.867783 0.0356773 0.495662 -0.864305 0.0854207 0.495662 -0.857549 0.137585 0.495662 -0.881878 0.149842 0.447033 -0.852788 0.164536 0.495662 -0.888892 0.100156 0.447033 -0.859556 0.247638 0.447033 -0.840175 0.220059 0.495662 -0.866163 0.223434 0.447033 -0.877329 0.174514 0.447033 -0.812503 0.306853 0.495662 -0.844319 0.295444 0.447033 -0.8357 0.319008 0.447033 -0.832187 0.248564 0.495662 -0.794728 0.41057 0.447033 -0.772666 0.396619 0.495662 -0.805931 0.38812 0.447033 -0.8165 0.365361 0.447033 -0.800667 0.336529 0.495662 -0.826425 0.342319 0.447033 -0.770458 0.454483 0.447033 -0.738462 0.457157 0.495662 -0.75637 0.426877 0.495662 -0.782902 0.432696 0.447033 -0.674549 0.547086 0.495662 -0.697597 0.517376 0.495662 -0.69936 0.557725 0.447033 -0.729533 0.517632 0.447033 -0.718887 0.487361 0.495662 -0.743762 0.496969 0.447033 -0.650009 0.614532 0.447033 -0.649711 0.576364 0.495662 -0.66699 0.596059 0.447033 -0.683443 0.577119 0.447033 -0.577116 0.683446 0.447033 -0.564298 0.660218 0.495662 -0.596058 0.66699 0.447033 -0.604345 0.586898 0.538812 -0.558001 0.594118 0.57936 -0.584721 0.567841 0.57936 -0.496965 0.743765 0.447033 -0.462751 0.73497 0.495662 -0.498338 0.711322 0.495662 -0.537888 0.714729 0.447033 -0.532203 0.686352 0.495662 -0.454482 0.770459 0.447033 -0.432694 0.782903 0.447033 -0.425507 0.757141 0.495662 -0.412726 0.734397 0.538812 -0.44885 0.712892 0.538812 -0.36536 0.8165 0.447033 -0.342316 0.826427 0.447033 -0.346401 0.796445 0.495662 -0.388115 0.805933 0.447033 -0.386691 0.777682 0.495662 -0.271644 0.852274 0.447033 -0.261892 0.828089 0.495662 -0.29544 0.84432 0.447033 -0.304757 0.813291 0.495662 -0.319003 0.835702 0.447033 -0.199048 0.87209 0.447033 -0.174511 0.87733 0.447033 -0.173114 0.851088 0.495662 -0.247633 0.859558 0.447033 -0.223428 0.866165 0.447033 -0.217956 0.840723 0.495662 -0.0814258 0.86469 0.495662 -0.127542 0.8591 0.495662 -0.100154 0.888893 0.447033 -0.149836 0.881879 0.447033 -0.0250867 0.894165 0.447033 8.14756e-08 0.894517 0.447033 -0.0349598 0.867812 0.495662 0.0113073 0.84235 0.538812 -0.0339096 0.841743 0.538812 0.0250893 0.894165 0.447033 0.0501576 0.89311 0.447033 0.0582242 0.866562 0.495662 0.0116574 0.868437 0.495662 0.150408 0.855393 0.495662 0.10454 0.862201 0.495662 0.125047 0.885734 0.447033 0.14589 0.829697 0.538812 0.1014 0.836301 0.538812 0.19905 0.87209 0.447033 0.223431 0.866164 0.447033 0.195638 0.846195 0.495662 0.149839 0.881878 0.447033 0.174512 0.877329 0.447033 0.271645 0.852274 0.447033 0.283468 0.820954 0.495662 0.240048 0.834683 0.495662 0.247636 0.859557 0.447033 0.342318 0.826426 0.447033 0.32574 0.805116 0.495662 0.319006 0.835701 0.447033 0.295442 0.844319 0.447033 0.40629 0.767625 0.495662 0.366723 0.787295 0.495662 0.388118 0.805931 0.447033 0.394085 0.744566 0.538812 0.355707 0.763645 0.538812 0.444331 0.74625 0.495662 0.466314 0.701593 0.538812 0.430984 0.723833 0.538812 0.410569 0.794729 0.447033 0.480756 0.723321 0.495662 0.475913 0.757408 0.447033 0.496969 0.743763 0.447033 0.454483 0.770459 0.447033 0.544 0.606964 0.57936 0.514724 0.631982 0.57936 0.531998 0.653192 0.538812 0.500004 0.677995 0.538812 0.467995 0.47577 0.744731 0.448894 0.416589 0.790536 0.429461 0.436595 0.790536 0.524116 0.584779 0.619141 -0.500746 -0.159094 -0.850848 -0.570826 -0.203884 -0.795355 -0.577688 -0.18354 -0.795355 0.339675 0.315229 0.886144 0.324969 0.330368 0.886144 0.382528 0.388883 0.838118 -0.841474 -0.411476 0.350154 -0.870811 -0.425822 0.245689 -0.824744 -0.44406 0.350154 -0.900422 -0.358996 -0.245689 -0.921142 -0.367257 -0.128917 -0.912867 -0.326053 -0.245689 -0.652287 -0.351205 0.671697 -0.702723 -0.378361 0.602514 -0.637705 -0.377034 0.671697 -0.806308 -0.476718 0.350154 -0.853498 -0.459541 0.245689 -0.163356 -0.115843 0.979743 -0.0449761 -0.0348826 0.998379 -0.0464286 -0.0329246 0.998379 -0.604301 -0.428536 0.671697 -0.651027 -0.461671 0.602514 -0.585395 -0.454022 0.671697 0.500048 0.508355 0.70109 0.475924 0.531008 0.70109 0.501754 0.559829 0.65942 -0.152725 -0.129536 0.979743 -0.0417202 -0.0387178 0.998379 -0.0434072 -0.0368166 0.998379 0.53789 0.714728 0.447033 0.548474 0.673421 0.495662 0.515489 0.698992 0.495662 0.517632 0.729533 0.447033 0.596059 0.66699 0.447033 0.57967 0.646763 0.495662 0.577119 0.683444 0.447033 0.557724 0.69936 0.447033 0.632521 0.632518 0.447033 0.609053 0.619172 0.495662 0.614532 0.650009 0.447033 0.66699 0.596058 0.447033 0.636613 0.590798 0.495662 0.650011 0.61453 0.447033 0.699363 0.55772 0.447033 0.662355 0.561787 0.495662 0.683446 0.577116 0.447033 0.714729 0.537888 0.447033 0.686294 0.532277 0.495662 0.729534 0.51763 0.447033 0.708459 0.502399 0.495662 0.728886 0.472275 0.495662 0.706991 0.458089 0.538812 0.757411 0.47591 0.447033 0.747621 0.44202 0.495662 0.743765 0.496965 0.447033 0.782903 0.432693 0.447033 0.764716 0.411739 0.495662 0.725163 0.428742 0.538812 0.741744 0.399371 0.538812 0.717659 0.386403 0.57936 0.756791 0.370067 0.538812 0.780228 0.381528 0.495662 0.794731 0.410564 0.447033 0.805933 0.388114 0.447033 0.794221 0.351473 0.495662 0.757115 0.30186 0.57936 0.782524 0.31199 0.538812 0.76758 0.27416 0.57936 0.8165 0.36536 0.447033 0.826427 0.342314 0.447033 0.806758 0.321653 0.495662 0.835703 0.319001 0.447033 0.817909 0.292137 0.495662 0.827743 0.262986 0.495662 0.844321 0.295438 0.447033 0.852274 0.271643 0.447033 0.836328 0.234253 0.495662 0.859558 0.24763 0.447033 0.802878 0.255086 0.538812 0.784865 0.219839 0.57936 0.776808 0.246803 0.57936 0.866165 0.223426 0.447033 0.843735 0.205985 0.495662 0.81839 0.199797 0.538812 0.824499 0.172866 0.538812 0.797727 0.167253 0.57936 0.87209 0.199047 0.447033 0.85529 0.15099 0.495662 0.850034 0.17822 0.495662 0.87733 0.174509 0.447033 0.881879 0.149833 0.447033 0.829598 0.146455 0.538812 0.859572 0.124323 0.495662 0.885735 0.125041 0.447033 0.862942 0.0982387 0.495662 0.888893 0.100153 0.447033 0.78024 0.0888238 0.619141 0.809841 0.0921936 0.57936 0.78252 0.0657818 0.619141 0.891352 0.0751808 0.447033 0.865463 0.0727543 0.495662 0.89311 0.0501504 0.447033 0.784989 0.0213642 0.619141 0.771317 3.75332e-16 0.636451 0.751497 0.0204527 0.65942 0.894166 0.0250843 0.447033 0.867195 0.0478817 0.495662 0.868194 0.0236287 0.495662 0.868462 5.21812e-16 0.495756 0.844452 3.61835e-16 0.535631 0.770459 0.454482 0.447033 0.687178 0.487307 0.538812 0.664865 0.471484 0.57936 0.665679 0.516288 0.538812 0.61749 0.573051 0.538812 0.642458 0.544912 0.538812 0.590758 0.600572 0.538812 0.562257 0.627334 0.538812 0.474751 0.582904 0.65942 0.450311 0.552895 0.70109 0.177018 0.164279 0.9704 0.266006 0.246862 0.931826 0.184176 0.156212 0.9704 0.25449 0.258718 0.931826 -0.428585 -0.303928 0.850848 -0.440942 -0.285705 0.850848 -0.508696 -0.329605 0.795355 -0.158245 -0.122732 0.979743 -0.26519 -0.188058 0.945679 -0.49444 -0.350628 0.795355 -0.568411 -0.368297 0.735709 -0.256893 -0.199242 0.945679 -0.352916 -0.250268 0.901563 -0.73161 -0.432554 0.52692 -0.669798 -0.43399 0.602514 -0.687014 -0.406187 0.602514 -0.583021 -0.344703 0.735709 -0.521771 -0.30849 0.795355 -0.805225 -0.393751 0.443366 -0.748338 -0.402921 0.52692 -0.763519 -0.373357 0.52692 -0.789215 -0.42493 0.443366 -0.914457 -0.404682 1.91753e-07 -0.906827 -0.401305 -0.128917 -0.906827 -0.401305 0.128917 -0.928893 -0.370347 1.91753e-07 -0.363091 -0.235262 0.901563 -0.886428 -0.392278 0.245689 -0.921142 -0.367257 0.128917 -0.856565 -0.379062 -0.350154 -0.841474 -0.411476 -0.350154 -0.870811 -0.425822 -0.245689 -0.882113 -0.315069 -0.350154 -0.870087 -0.346902 -0.350154 -0.800393 -0.28588 -0.526919 -0.789481 -0.314764 -0.526919 -0.832605 -0.331957 -0.443366 -0.844113 -0.301496 -0.443366 -0.854261 -0.271411 -0.443366 0.0756183 0.0641369 0.995072 -0.415176 -0.322003 0.850848 -0.329949 -0.279852 0.901563 -0.341874 -0.265151 0.901563 -0.810015 -0.257354 -0.526919 -0.751604 -0.268454 -0.602514 -0.760641 -0.241666 -0.602514 0.0783514 0.0607679 0.995072 -0.713371 -0.199813 -0.671697 -0.706047 -0.224321 -0.671697 0.0726795 0.067449 0.995072 -0.652197 -0.182679 -0.735709 -0.645502 -0.205085 -0.735709 -0.657974 -0.160634 -0.735709 -0.58885 -0.143759 -0.795355 0.399838 0.371063 0.838118 0.353409 0.29975 0.886144 -0.420303 -0.102611 -0.901563 -0.42344 -0.0887794 -0.901563 -0.318184 -0.0667112 -0.945679 -0.510421 -0.124611 -0.850848 -0.58368 -0.163487 -0.795355 -0.195999 -0.0410937 -0.979743 -0.315827 -0.0771043 -0.945679 -0.0542456 -0.0172346 -0.998379 -0.0548083 -0.0153516 -0.998379 0.0954803 0.0267438 -0.995072 0.0976452 0.017238 -0.995072 -0.0557064 -0.0116795 -0.998379 -0.0560509 -0.00989506 -0.998379 0.097045 0.0203467 -0.995072 0.237824 0.0419847 -0.9704 0.636035 0.202078 -0.744731 0.686646 0.192328 -0.70109 0.679597 0.215918 -0.70109 0.359168 0.0519477 -0.931826 0.239014 0.0345695 -0.9704 0.360576 0.0410486 -0.931826 0.608485 0.0692709 -0.790537 0.541988 0.0617008 -0.838118 0.610262 0.0513011 -0.790537 0.539871 0.0780834 -0.838118 0.458637 0.0663343 -0.886144 0.710566 0.0597331 -0.70109 0.708496 0.0806564 -0.70109 0.663082 0.0754864 -0.744731 0.665019 0.0559042 -0.744731 0.771327 8.81105e-17 -0.63644 0.784989 0.0213642 -0.619141 0.751497 0.0204527 -0.65942 0.749133 0.0629751 -0.65942 0.809841 0.0921936 -0.57936 0.812207 0.0682774 -0.57936 0.839465 0.0705689 -0.538812 0.81477 0.0221747 -0.57936 0.796815 3.4965e-16 -0.604223 0.89311 0.0501621 -0.447033 0.867195 0.0478817 -0.495662 0.894166 0.0250843 -0.447033 0.841145 0.0464433 -0.538812 0.842114 0.0229189 -0.538812 0.868194 0.0236287 -0.495662 0.432696 0.782902 0.447033 0.460435 0.0524167 -0.886144 -0.194547 -0.0474957 -0.979743 -0.50594 -0.141712 -0.850848 0.364074 0.406212 0.838118 0.408742 0.456051 0.790536 0.445417 0.496971 0.744731 0.421446 0.517455 0.744731 -0.0751835 0.891352 0.447033 -0.0501543 0.89311 0.447033 0.365361 0.8165 0.447033 0.266025 0.770437 0.57936 0.225277 0.783321 0.57936 0.232837 0.80961 0.538812 0.315955 0.780931 0.538812 0.189761 0.820776 0.538812 0.0751854 0.891352 0.447033 0.100155 0.888893 0.447033 0.0564751 0.840531 0.538812 -0.125044 0.885734 0.447033 -0.0789798 0.838716 0.538812 -0.123711 0.833293 0.538812 -0.162462 0.798717 0.57936 -0.204545 0.788989 0.57936 -0.211409 0.815468 0.538812 -0.254025 0.803214 0.538812 -0.295602 0.788861 0.538812 -0.335996 0.772521 0.538812 -0.399324 0.710551 0.57936 -0.362896 0.729828 0.57936 -0.410565 0.794731 0.447033 -0.475911 0.75741 0.447033 -0.517631 0.729534 0.447033 -0.632518 0.632521 0.447033 -0.623061 0.605074 0.495662 -0.483368 0.689954 0.538812 -0.557721 0.699363 0.447033 -0.594589 0.633074 0.495662 -0.61453 0.650011 0.447033 -0.516216 0.665735 0.538812 -0.547347 0.640385 0.538812 -0.654286 0.530652 0.538812 -0.609731 0.540897 0.57936 -0.633041 0.513422 0.57936 -0.714728 0.53789 0.447033 -0.697293 0.472721 0.538812 -0.676641 0.501835 0.538812 -0.757408 0.475915 0.447033 -0.716279 0.443425 0.538812 -0.733649 0.414054 0.538812 -0.78741 0.366475 0.495662 -0.788096 0.297635 0.538812 -0.776616 0.32642 0.538812 -0.822986 0.277512 0.495662 -0.852274 0.271645 0.447033 -0.847019 0.192038 0.495662 -0.861367 0.111207 0.495662 -0.872089 0.199052 0.447033 -0.885733 0.12505 0.447033 0.820904 1.32565e-16 0.571067 0.842114 0.0229189 0.538812 0.678158 -1.17774e-16 0.734916 0.712809 0.0193997 0.70109 0.712911 7.4781e-17 0.701254 0.81477 0.0221747 0.57936 0.841145 0.0464433 0.538812 0.839465 0.0705689 0.538812 0.83702 0.0952877 0.538812 0.833751 0.120588 0.538812 0.74695 0.0850341 0.65942 0.744033 0.107612 0.65942 0.777193 0.112408 0.619141 0.811206 0.227217 0.538812 0.79334 0.283361 0.538812 0.770363 0.340915 0.538812 0.745349 0.329845 0.57936 0.729441 0.290826 0.619141 0.718105 0.317789 0.619141 0.684035 0.443214 0.57936 0.701617 0.414821 0.57936 0.675971 0.399658 0.619141 0.621597 0.527218 0.57936 0.620522 0.481266 0.619141 0.598877 0.507947 0.619141 0.59744 0.554444 0.57936 0.571575 0.581071 0.57936 0.451173 0.678812 0.57936 0.41699 0.70033 0.57936 0.381289 0.720389 0.57936 0.344157 0.738849 0.57936 0.294522 0.727956 0.619141 0.256301 0.742276 0.619141 0.274953 0.796293 0.538812 0.1836 0.794124 0.57936 0.141153 0.802757 0.57936 0.0981072 0.809146 0.57936 0.0546414 0.813238 0.57936 0.0109401 0.814998 0.57936 -0.0328085 0.814411 0.57936 -0.0764153 0.811482 0.57936 -0.115319 0.776766 0.619141 -0.156524 0.769522 0.619141 -0.167914 0.825522 0.538812 -0.245777 0.777133 0.57936 -0.286004 0.763246 0.57936 -0.325086 0.747437 0.57936 -0.375075 0.754321 0.538812 -0.434276 0.689744 0.57936 -0.499454 0.644118 0.57936 -0.450579 0.643151 0.619141 -0.481198 0.620574 0.619141 -0.529574 0.619592 0.57936 -0.576728 0.614057 0.538812 -0.630194 0.55905 0.538812 -0.65467 0.48554 0.57936 -0.674651 0.457371 0.57936 -0.72512 0.372213 0.57936 -0.683882 0.385966 0.619141 -0.698616 0.358608 0.619141 -0.749456 0.384705 0.538812 -0.763757 0.355467 0.538812 -0.751398 0.315821 0.57936 -0.762506 0.287971 0.57936 -0.798265 0.269176 0.538812 -0.807189 0.241097 0.538812 -0.814937 0.213448 0.538812 -0.821575 0.186269 0.538812 -0.827171 0.159594 0.538812 -0.831789 0.133452 0.538812 -0.835492 0.107866 0.538812 -0.838342 0.0828548 0.538812 -0.840397 0.0584315 0.538812 -0.841715 0.0346056 0.538812 -0.842349 0.0113837 0.538812 -0.842349 -0.0113835 0.538812 -0.841715 -0.0346058 0.538812 -0.840397 -0.0584315 0.538812 -0.835492 -0.107866 0.538812 -0.831789 -0.133452 0.538812 -0.827171 -0.159594 0.538812 -0.794898 -0.18022 0.57936 -0.788475 -0.206517 0.57936 -0.807189 -0.241098 0.538812 -0.772344 -0.260436 0.57936 -0.762506 -0.287971 0.57936 -0.776616 -0.32642 0.538812 -0.763757 -0.355467 0.538812 -0.733649 -0.414054 0.538812 -0.65467 -0.48554 0.57936 -0.649991 -0.440653 0.619141 -0.630741 -0.467793 0.619141 -0.633041 -0.513422 0.57936 -0.630194 -0.55905 0.538812 -0.558002 -0.594118 0.57936 -0.529574 -0.619592 0.57936 -0.516216 -0.665735 0.538812 -0.434276 -0.689744 0.57936 -0.399324 -0.710551 0.57936 -0.362896 -0.729828 0.57936 -0.313203 -0.720117 0.619141 -0.27555 -0.735348 0.619141 -0.295602 -0.788861 0.538812 -0.204544 -0.788989 0.57936 -0.162462 -0.798717 0.57936 -0.119694 -0.806235 0.57936 -0.0764154 -0.811482 0.57936 -0.0328084 -0.814411 0.57936 0.01094 -0.814999 0.57936 0.0546411 -0.813238 0.57936 0.0981071 -0.809146 0.57936 0.135994 -0.773414 0.619141 0.176889 -0.765098 0.619141 0.1836 -0.794124 0.57936 0.225277 -0.783321 0.57936 0.394085 -0.744566 0.538812 0.430984 -0.723833 0.538812 0.466314 -0.701593 0.538812 0.500004 -0.677995 0.538812 0.531998 -0.653192 0.538812 0.562257 -0.627334 0.538812 0.590758 -0.600572 0.538812 0.61749 -0.573051 0.538812 0.642459 -0.544912 0.538812 0.665679 -0.516288 0.538812 0.687178 -0.487307 0.538812 0.544001 -0.606964 0.57936 0.571575 -0.581071 0.57936 0.725163 -0.428743 0.538812 0.706991 -0.458089 0.538812 0.741744 -0.399371 0.538812 0.756791 -0.370067 0.538812 0.770363 -0.340915 0.538812 0.782524 -0.31199 0.538812 0.701617 -0.414821 0.57936 0.79334 -0.283361 0.538812 0.802878 -0.255086 0.538812 0.811205 -0.227217 0.538812 0.81839 -0.199797 0.538812 0.776808 -0.246803 0.57936 0.76758 -0.27416 0.57936 0.829598 -0.146455 0.538812 0.833751 -0.120588 0.538812 0.83702 -0.0952876 0.538812 0.80266 -0.141699 0.57936 0.839465 -0.0705688 0.538812 0.842114 -0.022919 0.538812 0.796809 2.20951e-17 0.604231 0.813832 0.0449353 0.57936 0.812207 0.0682774 0.57936 0.806678 0.116673 0.57936 0.80266 0.141699 0.57936 0.740327 0.130695 0.65942 0.702214 0.123967 0.70109 0.735777 0.154265 0.65942 0.791817 0.19331 0.57936 0.756177 0.211803 0.619141 0.762874 0.186244 0.619141 0.730326 0.178298 0.65942 0.707971 0.252869 0.65942 0.739523 0.264139 0.619141 0.716482 0.227637 0.65942 0.732217 0.35805 0.57936 0.691428 0.372279 0.619141 0.705454 0.344963 0.619141 0.675355 0.330245 0.65942 0.659032 0.427014 0.619141 0.630914 0.408795 0.65942 0.640563 0.454251 0.619141 0.644064 0.499524 0.57936 0.575602 0.534178 0.619141 0.573325 0.486275 0.65942 0.551044 0.511387 0.65942 0.550683 0.559832 0.619141 0.434682 0.654 0.619141 0.401748 0.674732 0.619141 0.367352 0.694058 0.619141 0.31743 0.681472 0.65942 0.281956 0.696898 0.65942 0.305696 0.755574 0.57936 0.217043 0.75469 0.619141 0.176889 0.765098 0.619141 0.135993 0.773414 0.619141 0.0945212 0.77957 0.619141 0.0526441 0.783513 0.619141 0.0105402 0.785209 0.619141 -0.0316093 0.784643 0.619141 -0.070481 0.748464 0.65942 -0.110399 0.743625 0.65942 -0.119694 0.806235 0.57936 -0.197068 0.76015 0.619141 -0.236793 0.748728 0.619141 -0.27555 0.735348 0.619141 -0.29984 0.689392 0.65942 -0.334714 0.673151 0.65942 -0.349631 0.703151 0.619141 -0.384728 0.684579 0.619141 -0.418402 0.664533 0.619141 -0.467673 0.667551 0.57936 -0.510217 0.596944 0.619141 -0.537606 0.572402 0.619141 -0.563349 0.547085 0.619141 -0.587445 0.521127 0.619141 -0.609902 0.494655 0.619141 -0.630741 0.467793 0.619141 -0.649991 0.440653 0.619141 -0.693021 0.429026 0.57936 -0.709827 0.400609 0.57936 -0.738957 0.343925 0.57936 -0.744114 0.250916 0.619141 -0.703291 0.265607 0.65942 -0.712365 0.24021 0.65942 -0.772344 0.260435 0.57936 -0.780979 0.233269 0.57936 -0.788475 0.206517 0.57936 -0.794898 0.180221 0.57936 -0.800312 0.154412 0.57936 -0.80478 0.129119 0.57936 -0.808363 0.104364 0.57936 -0.81112 0.0801644 0.57936 -0.813109 0.0565341 0.57936 -0.814384 0.0334819 0.57936 -0.814997 0.011014 0.57936 -0.814997 -0.0110139 0.57936 -0.814384 -0.0334821 0.57936 -0.778816 -0.100549 0.619141 -0.74813 -0.073939 0.65942 -0.745587 -0.0962589 0.65942 -0.808363 -0.104364 0.57936 -0.80478 -0.129119 0.57936 -0.800312 -0.154412 0.57936 -0.752433 -0.224743 0.619141 -0.727243 -0.19048 0.65942 -0.720329 -0.215154 0.65942 -0.780979 -0.233269 0.57936 -0.703291 -0.265607 0.65942 -0.693046 -0.291295 0.65942 -0.723934 -0.304277 0.619141 -0.751398 -0.315821 0.57936 -0.711947 -0.331353 0.619141 -0.698616 -0.358608 0.619141 -0.683882 -0.385966 0.619141 -0.66769 -0.413345 0.619141 -0.674651 -0.457371 0.57936 -0.609902 -0.494655 0.619141 -0.587444 -0.521127 0.619141 -0.563349 -0.547085 0.619141 -0.537606 -0.572402 0.619141 -0.488448 -0.571475 0.65942 -0.460668 -0.594097 0.65942 -0.481198 -0.620574 0.619141 -0.450579 -0.643151 0.619141 -0.418402 -0.664533 0.619141 -0.384728 -0.684579 0.619141 -0.349631 -0.703151 0.619141 -0.325086 -0.747437 0.57936 -0.236793 -0.748728 0.619141 -0.197068 -0.76015 0.619141 -0.156524 -0.769522 0.619141 -0.115319 -0.776766 0.619141 -0.0736223 -0.781821 0.619141 -0.0316092 -0.784643 0.619141 0.0105401 -0.785209 0.619141 0.0526438 -0.783513 0.619141 0.0904883 -0.746309 0.65942 0.130191 -0.740416 0.65942 0.141153 -0.802757 0.57936 0.217043 -0.75469 0.619141 0.256301 -0.742276 0.619141 0.381289 -0.720389 0.57936 0.41699 -0.70033 0.57936 0.451173 -0.678812 0.57936 0.483769 -0.65598 0.57936 0.514724 -0.631982 0.57936 0.560074 -0.362895 0.744731 0.57447 -0.339647 0.744731 0.613815 -0.36291 0.70109 0.59744 -0.554444 0.57936 0.621598 -0.527218 0.57936 0.644064 -0.499524 0.57936 0.664865 -0.471484 0.57936 0.524116 -0.584779 0.619141 0.684035 -0.443214 0.57936 0.717659 -0.386403 0.57936 0.732217 -0.35805 0.57936 0.745349 -0.329845 0.57936 0.757115 -0.30186 0.57936 0.675971 -0.399659 0.619141 0.784865 -0.219839 0.57936 0.791817 -0.19331 0.57936 0.748414 -0.237782 0.619141 0.739523 -0.264139 0.619141 0.797727 -0.167253 0.57936 0.806678 -0.116673 0.57936 0.809841 -0.0921935 0.57936 0.812207 -0.0682774 0.57936 0.78024 -0.0888237 0.619141 0.78252 -0.0657817 0.619141 0.81477 -0.0221748 0.57936 0.813832 -0.0449353 0.57936 0.470979 -2.79194e-17 0.882144 0.463238 0.0126075 0.886144 0.536527 2.22653e-16 0.843883 0.784085 0.0432928 0.619141 0.612188 0.0166613 0.790536 0.591571 -2.48107e-17 0.806253 0.545287 0.0148405 0.838118 0.773322 0.13652 0.619141 0.768569 0.16114 0.619141 0.748414 0.237782 0.619141 0.698319 0.278418 0.65942 0.671524 0.239851 0.70109 0.662368 0.264085 0.70109 0.64713 0.382607 0.65942 0.661927 0.356396 0.65942 0.627851 0.338048 0.70109 0.613232 0.43487 0.65942 0.527188 0.535946 0.65942 0.522675 0.48506 0.70109 0.4462 0.605038 0.65942 0.416136 0.626096 0.65942 0.384607 0.645943 0.65942 0.333574 0.630239 0.70109 0.301089 0.646389 0.70109 0.331577 0.711843 0.619141 0.245366 0.710606 0.65942 0.207782 0.72249 0.65942 0.169342 0.732454 0.65942 0.130191 0.740416 0.65942 0.0904884 0.746309 0.65942 0.050398 0.750084 0.65942 0.0100905 0.751707 0.65942 -0.0287028 0.712495 0.70109 -0.0668526 0.709932 0.70109 -0.0736222 0.781821 0.619141 -0.149845 0.73669 0.65942 -0.18866 0.727718 0.65942 -0.22669 0.716783 0.65942 -0.263793 0.703974 0.65942 -0.313203 0.720117 0.619141 -0.368313 0.655371 0.65942 -0.400551 0.63618 0.65942 -0.431354 0.61571 0.65942 -0.460667 0.594097 0.65942 -0.488448 0.571475 0.65942 -0.514668 0.54798 0.65942 -0.539313 0.523743 0.65942 -0.562381 0.498892 0.65942 -0.58388 0.47355 0.65942 -0.60383 0.447834 0.65942 -0.622259 0.421852 0.65942 -0.66769 0.413345 0.619141 -0.654703 0.369499 0.65942 -0.668809 0.343308 0.65942 -0.711947 0.331354 0.619141 -0.723934 0.304277 0.619141 -0.734635 0.277445 0.619141 -0.752433 0.224743 0.619141 -0.759655 0.198969 0.619141 -0.765843 0.173633 0.619141 -0.771059 0.148768 0.619141 -0.775364 0.124399 0.619141 -0.778816 0.100549 0.619141 -0.781472 0.0772343 0.619141 -0.783388 0.0544677 0.619141 -0.784617 0.0322581 0.619141 -0.785208 0.0106114 0.619141 -0.785208 -0.0106113 0.619141 -0.784617 -0.0322583 0.619141 -0.783388 -0.0544677 0.619141 -0.781472 -0.0772343 0.619141 -0.775364 -0.124399 0.619141 -0.771059 -0.148768 0.619141 -0.765843 -0.173633 0.619141 -0.759655 -0.198969 0.619141 -0.744114 -0.250916 0.619141 -0.734635 -0.277445 0.619141 -0.681571 -0.317216 0.65942 -0.668809 -0.343308 0.65942 -0.654703 -0.369499 0.65942 -0.639203 -0.395709 0.65942 -0.622259 -0.421852 0.65942 -0.60383 -0.447834 0.65942 -0.58388 -0.47355 0.65942 -0.562381 -0.498892 0.65942 -0.539313 -0.523743 0.65942 -0.514668 -0.54798 0.65942 -0.510217 -0.596945 0.619141 -0.431354 -0.61571 0.65942 -0.400551 -0.63618 0.65942 -0.368313 -0.655371 0.65942 -0.317483 -0.638496 0.70109 -0.284404 -0.653901 0.70109 -0.29984 -0.689392 0.65942 -0.263793 -0.703973 0.65942 -0.22669 -0.716783 0.65942 -0.18866 -0.727718 0.65942 -0.149845 -0.73669 0.65942 -0.110399 -0.743625 0.65942 -0.0704812 -0.748464 0.65942 -0.0302605 -0.751166 0.65942 0.0100904 -0.751707 0.65942 0.0478032 -0.711469 0.70109 0.0858298 -0.707888 0.70109 0.0945211 -0.77957 0.619141 0.169342 -0.732454 0.65942 0.207782 -0.72249 0.65942 0.245366 -0.710606 0.65942 0.267441 -0.66102 0.70109 0.401748 -0.674732 0.619141 0.434682 -0.654 0.619141 0.466086 -0.632003 0.619141 0.49591 -0.608882 0.619141 0.281957 -0.696897 0.65942 0.575603 -0.534178 0.619141 0.598877 -0.507947 0.619141 0.620522 -0.481265 0.619141 0.640563 -0.454251 0.619141 0.675355 -0.330245 0.65942 0.705454 -0.344963 0.619141 0.661927 -0.356396 0.65942 0.659032 -0.427014 0.619141 0.691428 -0.372279 0.619141 0.718105 -0.317789 0.619141 0.729441 -0.290826 0.619141 0.64713 -0.382607 0.65942 0.756177 -0.211803 0.619141 0.762874 -0.186244 0.619141 0.768569 -0.16114 0.619141 0.773322 -0.13652 0.619141 0.777193 -0.112408 0.619141 0.740327 -0.130695 0.65942 0.74695 -0.0850339 0.65942 0.749133 -0.0629751 0.65942 0.784989 -0.0213643 0.619141 0.784085 -0.0432929 0.619141 0.743636 2.36559e-17 0.668584 0.750632 0.0414457 0.65942 0.749133 0.0629751 0.65942 0.663082 0.0754864 0.744731 0.610263 0.0513012 0.790536 0.608485 0.0692709 0.790536 0.599383 0.125668 0.790536 0.648324 0.158278 0.744731 0.653163 0.136944 0.744731 0.723914 0.202766 0.65942 0.636035 0.202078 0.744731 0.679597 0.215918 0.70109 0.642632 0.18 0.744731 0.687466 0.30423 0.65942 0.652075 0.288568 0.70109 0.619911 0.247157 0.744731 0.610277 0.270071 0.744731 0.613815 0.36291 0.70109 0.598434 0.38775 0.70109 0.560074 0.362895 0.744731 0.581663 0.412482 0.70109 0.594047 0.460732 0.65942 0.563465 0.437013 0.70109 0.54381 0.461241 0.70109 0.423229 0.57389 0.70109 0.394713 0.593864 0.70109 0.364807 0.61269 0.70109 0.351679 0.664445 0.65942 0.267441 0.66102 0.70109 0.232734 0.674023 0.70109 0.197085 0.685296 0.70109 0.160624 0.694746 0.70109 0.123489 0.702299 0.70109 0.08583 0.707888 0.70109 0.0478035 0.711469 0.70109 0.00895755 0.667305 0.744731 -0.026863 0.666824 0.744731 -0.0302607 0.751166 0.65942 -0.104715 0.705342 0.70109 -0.142131 0.698764 0.70109 -0.178948 0.690254 0.70109 -0.21502 0.679882 0.70109 -0.234174 0.624931 0.744731 -0.266174 0.611987 0.744731 -0.284404 0.653901 0.70109 -0.317483 0.638496 0.70109 -0.349352 0.621632 0.70109 -0.355577 0.564749 0.744731 -0.382922 0.546578 0.744731 -0.409148 0.584013 0.70109 -0.436952 0.563512 0.70109 -0.433605 0.507309 0.744731 -0.456881 0.486453 0.744731 -0.488172 0.51977 0.70109 -0.511549 0.49678 0.70109 -0.533429 0.473209 0.70109 -0.553821 0.449171 0.70109 -0.606296 0.375338 0.70109 -0.552391 0.374487 0.744731 -0.567432 0.351279 0.744731 -0.639203 0.395709 0.65942 -0.620998 0.350476 0.70109 -0.634378 0.325634 0.70109 -0.681571 0.317216 0.65942 -0.693046 0.291295 0.65942 -0.667085 0.251934 0.70109 -0.675692 0.227844 0.70109 -0.720329 0.215154 0.65942 -0.727243 0.19048 0.65942 -0.733168 0.166225 0.65942 -0.738161 0.14242 0.65942 -0.742282 0.119092 0.65942 -0.745587 0.0962591 0.65942 -0.74813 0.073939 0.65942 -0.749964 0.0521438 0.65942 -0.75114 0.0308818 0.65942 -0.751706 0.0101587 0.65942 -0.751706 -0.0101586 0.65942 -0.75114 -0.030882 0.65942 -0.749964 -0.0521438 0.65942 -0.704069 -0.112961 0.70109 -0.661872 -0.0854509 0.744731 -0.658938 -0.10572 0.744731 -0.742282 -0.119092 0.65942 -0.738161 -0.14242 0.65942 -0.733168 -0.166225 0.65942 -0.689804 -0.180674 0.70109 -0.683246 -0.204077 0.70109 -0.712365 -0.240211 0.65942 -0.667085 -0.251934 0.70109 -0.657367 -0.276298 0.70109 -0.646483 -0.300885 0.70109 -0.634378 -0.325634 0.70109 -0.620998 -0.350476 0.70109 -0.606296 -0.375338 0.70109 -0.590224 -0.400135 0.70109 -0.572744 -0.424779 0.70109 -0.518321 -0.42038 0.744731 -0.499236 -0.442876 0.744731 -0.533429 -0.473209 0.70109 -0.511549 -0.49678 0.70109 -0.456881 -0.486452 0.744731 -0.433605 -0.50731 0.744731 -0.463302 -0.542055 0.70109 -0.436952 -0.563512 0.70109 -0.409148 -0.584013 0.70109 -0.37993 -0.603428 0.70109 -0.326959 -0.581785 0.744731 -0.297132 -0.597569 0.744731 -0.334714 -0.673151 0.65942 -0.250213 -0.667732 0.70109 -0.21502 -0.679882 0.70109 -0.178948 -0.690254 0.70109 -0.142131 -0.698764 0.70109 -0.104715 -0.705342 0.70109 -0.0668527 -0.709932 0.70109 -0.0268628 -0.666824 0.744731 0.00895744 -0.667305 0.744731 0.00957093 -0.713008 0.70109 0.044739 -0.665864 0.744731 0.0503977 -0.750084 0.65942 0.123489 -0.702298 0.70109 0.160624 -0.694746 0.70109 0.197085 -0.685296 0.70109 0.232734 -0.674023 0.70109 0.416135 -0.626096 0.65942 0.4462 -0.605038 0.65942 0.474752 -0.582904 0.65942 0.551044 -0.511387 0.65942 0.573325 -0.486275 0.65942 0.594047 -0.460732 0.65942 0.613232 -0.43487 0.65942 0.500048 -0.508355 0.70109 0.475924 -0.531008 0.70109 0.630914 -0.408795 0.65942 0.687466 -0.30423 0.65942 0.698319 -0.278418 0.65942 0.707971 -0.252869 0.65942 0.716482 -0.227637 0.65942 0.723914 -0.202767 0.65942 0.730326 -0.178298 0.65942 0.671524 -0.239851 0.70109 0.679597 -0.215918 0.70109 0.735777 -0.154265 0.65942 0.744033 -0.107612 0.65942 0.702214 -0.123967 0.70109 0.708496 -0.0806563 0.70109 0.710566 -0.0597331 0.70109 0.751497 -0.0204528 0.65942 0.750632 -0.0414457 0.65942 0.667118 0.0181562 0.744731 0.711988 0.039312 0.70109 0.710566 0.0597331 0.70109 0.708496 0.0806564 0.70109 0.705729 0.102072 0.70109 0.541988 0.0617008 0.838118 0.539871 0.0780834 0.838118 0.606108 0.0876635 0.790536 0.697898 0.146323 0.70109 0.692728 0.169119 0.70109 0.686646 0.192328 0.70109 0.576731 0.205994 0.790536 0.628479 0.224477 0.744731 0.583665 0.185439 0.790536 0.640587 0.313243 0.70109 0.599525 0.293165 0.744731 0.57447 0.339647 0.744731 0.587606 0.316379 0.744731 0.539223 0.290329 0.790536 0.544378 0.386042 0.744731 0.499555 0.354256 0.790536 0.527347 0.409 0.744731 0.489172 0.453968 0.744731 0.467045 0.396132 0.790536 0.3961 0.537104 0.744731 0.369412 0.555798 0.744731 0.313311 0.526202 0.790536 0.286487 0.541274 0.790536 0.312192 0.589841 0.744731 0.281789 0.604955 0.744731 0.250298 0.618649 0.744731 0.217816 0.630819 0.744731 0.184452 0.641368 0.744731 0.150328 0.650214 0.744731 0.115573 0.657281 0.744731 0.0737142 0.607962 0.790536 0.0410555 0.611037 0.790536 0.0447393 0.665864 0.744731 0.00822 0.61236 0.790536 0.00957105 0.713008 0.70109 -0.0625674 0.664426 0.744731 -0.098003 0.66013 0.744731 -0.133021 0.653974 0.744731 -0.167477 0.646009 0.744731 -0.201237 0.636302 0.744731 -0.250213 0.667732 0.70109 -0.297132 0.597569 0.744731 -0.326959 0.581785 0.744731 -0.37993 0.603428 0.70109 -0.408943 0.527391 0.744731 -0.463302 0.542055 0.70109 -0.499236 0.442876 0.744731 -0.439338 0.426655 0.790536 -0.45813 0.40641 0.790536 -0.518321 0.42038 0.744731 -0.572744 0.424779 0.70109 -0.590224 0.400135 0.70109 -0.605044 0.281599 0.744731 -0.544829 0.279667 0.790536 -0.555225 0.258412 0.790536 -0.646483 0.300885 0.70109 -0.657367 0.276298 0.70109 -0.63945 0.190996 0.744731 -0.580311 0.195681 0.790536 -0.586799 0.17527 0.790536 -0.683246 0.204077 0.70109 -0.689804 0.180674 0.70109 -0.695423 0.157668 0.70109 -0.70016 0.135088 0.70109 -0.704069 0.112961 0.70109 -0.707203 0.0913036 0.70109 -0.709615 0.0701325 0.70109 -0.711355 0.0494594 0.70109 -0.712471 0.029292 0.70109 -0.713008 0.00963571 0.70109 -0.713008 -0.00963558 0.70109 -0.712471 -0.0292921 0.70109 -0.711355 -0.0494594 0.70109 -0.709615 -0.0701325 0.70109 -0.707203 -0.0913034 0.70109 -0.70016 -0.135088 0.70109 -0.695423 -0.157667 0.70109 -0.645588 -0.169092 0.744731 -0.63945 -0.190996 0.744731 -0.675692 -0.227844 0.70109 -0.624325 -0.235785 0.744731 -0.61523 -0.258588 0.744731 -0.605044 -0.281599 0.744731 -0.593714 -0.304761 0.744731 -0.581193 -0.328011 0.744731 -0.567432 -0.351279 0.744731 -0.552391 -0.374486 0.744731 -0.536031 -0.397551 0.744731 -0.553821 -0.449171 0.70109 -0.478759 -0.464937 0.744731 -0.488173 -0.519769 0.70109 -0.408943 -0.527391 0.744731 -0.382922 -0.546578 0.744731 -0.326299 -0.518248 0.790536 -0.300037 -0.533882 0.790536 -0.349352 -0.621632 0.70109 -0.266174 -0.611987 0.744731 -0.234175 -0.624931 0.744731 -0.201237 -0.636302 0.744731 -0.167477 -0.646009 0.744731 -0.133021 -0.653974 0.744731 -0.098003 -0.66013 0.744731 -0.0574157 -0.609718 0.790536 -0.024651 -0.611919 0.790536 -0.0287027 -0.712495 0.70109 0.0803282 -0.662513 0.744731 0.115573 -0.657281 0.744731 0.150328 -0.650213 0.744731 0.184452 -0.641368 0.744731 0.250298 -0.618649 0.744731 0.199881 -0.578878 0.790536 0.229689 -0.56771 0.790536 0.281789 -0.604955 0.744731 0.394712 -0.593864 0.70109 0.423229 -0.57389 0.70109 0.450311 -0.552895 0.70109 0.522676 -0.48506 0.70109 0.54381 -0.461241 0.70109 0.563465 -0.437013 0.70109 0.581663 -0.412482 0.70109 0.445417 -0.496971 0.744731 0.467995 -0.47577 0.744731 0.598434 -0.38775 0.70109 0.62785 -0.338048 0.70109 0.640587 -0.313243 0.70109 0.652075 -0.288568 0.70109 0.662368 -0.264085 0.70109 0.686646 -0.192328 0.70109 0.692728 -0.169119 0.70109 0.636035 -0.202078 0.744731 0.628479 -0.224477 0.744731 0.697899 -0.146323 0.70109 0.705729 -0.102072 0.70109 0.657203 -0.116021 0.744731 0.663082 -0.0754863 0.744731 0.665019 -0.0559042 0.744731 0.711988 -0.039312 0.70109 0.712809 -0.0193998 0.70109 0.638195 3.39784e-17 0.769875 0.66635 0.0367921 0.744731 0.665019 0.0559042 0.744731 0.660492 0.0955293 0.744731 0.657203 0.116021 0.744731 0.589719 0.165179 0.790536 0.594942 0.145246 0.790536 0.529925 0.129373 0.838118 0.568868 0.226806 0.790536 0.560027 0.247833 0.790536 0.506701 0.20202 0.838118 0.498826 0.220749 0.838118 0.513958 0.333015 0.790536 0.527169 0.311681 0.790536 0.469558 0.27762 0.838118 0.508952 0.431676 0.744731 0.386745 0.474848 0.790536 0.363486 0.492879 0.790536 0.301948 0.454296 0.838118 0.279071 0.468697 0.838118 0.341423 0.573416 0.744731 0.258587 0.555144 0.790536 0.229689 0.56771 0.790536 0.199881 0.578878 0.790536 0.169265 0.588559 0.790536 0.13795 0.596676 0.790536 0.0656585 0.541523 0.838118 0.0944668 0.537247 0.838118 0.0803283 0.662513 0.744731 -0.0246511 0.611919 0.790536 -0.0574156 0.609718 0.790536 -0.0899336 0.605776 0.790536 -0.122068 0.600126 0.790536 -0.153687 0.592817 0.790536 -0.214893 0.573475 0.790536 -0.164487 0.520098 0.838118 -0.191409 0.510804 0.838118 -0.244257 0.561596 0.790536 -0.272667 0.548366 0.790536 -0.300037 0.533882 0.790536 -0.326299 0.518248 0.790536 -0.351392 0.501573 0.790536 -0.375271 0.483966 0.790536 -0.397902 0.465538 0.790536 -0.419262 0.446399 0.790536 -0.478759 0.464937 0.744731 -0.491895 0.364817 0.790536 -0.423664 0.343609 0.838118 -0.43814 0.324949 0.838118 -0.536031 0.397551 0.744731 -0.506908 0.343652 0.790536 -0.520711 0.322355 0.790536 -0.581193 0.328011 0.744731 -0.593714 0.304761 0.744731 -0.61523 0.258588 0.744731 -0.624325 0.235785 0.744731 -0.63238 0.213239 0.744731 -0.645588 0.169092 0.744731 -0.650847 0.147561 0.744731 -0.65528 0.126429 0.744731 -0.658938 0.10572 0.744731 -0.661872 0.085451 0.744731 -0.664129 0.0656371 0.744731 -0.665758 0.0462891 0.744731 -0.666802 0.0274144 0.744731 -0.667304 0.00901807 0.744731 -0.667304 -0.00901795 0.744731 -0.666802 -0.0274145 0.744731 -0.665758 -0.0462891 0.744731 -0.664129 -0.0656371 0.744731 -0.601325 -0.116019 0.790536 -0.538601 -0.086413 0.838118 -0.535611 -0.10334 0.838118 -0.65528 -0.126429 0.744731 -0.650847 -0.147561 0.744731 -0.580311 -0.195682 0.790536 -0.522672 -0.156116 0.838118 -0.516893 -0.174297 0.838118 -0.63238 -0.21324 0.744731 -0.572919 -0.21637 0.790536 -0.564573 -0.237296 0.790536 -0.533338 -0.301003 0.790536 -0.485288 -0.249105 0.838118 -0.475053 -0.268109 0.838118 -0.506908 -0.343652 0.790536 -0.463806 -0.287127 0.838118 -0.451512 -0.306097 0.838118 -0.491895 -0.364817 0.790536 -0.475643 -0.385766 0.790536 -0.458129 -0.40641 0.790536 -0.439338 -0.426655 0.790536 -0.419262 -0.446399 0.790536 -0.397902 -0.465538 0.790536 -0.375271 -0.483966 0.790536 -0.351392 -0.501573 0.790536 -0.355577 -0.564749 0.744731 -0.272667 -0.548366 0.790536 -0.244257 -0.561596 0.790536 -0.214893 -0.573475 0.790536 -0.184667 -0.583909 0.790536 -0.153687 -0.592817 0.790536 -0.122068 -0.600126 0.790536 -0.0801054 -0.539575 0.838118 -0.0511412 -0.543086 0.838118 -0.0625675 -0.664426 0.744731 0.0082199 -0.61236 0.790536 0.0410553 -0.611037 0.790536 0.0737141 -0.607962 0.790536 0.106057 -0.603162 0.790536 0.13795 -0.596676 0.790536 0.169265 -0.588559 0.790536 0.217816 -0.630819 0.744731 0.258587 -0.555144 0.790536 0.3961 -0.537104 0.744731 0.421446 -0.517455 0.744731 0.489172 -0.453968 0.744731 0.508952 -0.431676 0.744731 0.429461 -0.436596 0.790536 0.408742 -0.456051 0.790536 0.469558 -0.27762 0.838118 0.398904 -0.235847 0.886144 0.480295 -0.258601 0.838118 0.587605 -0.316379 0.744731 0.599525 -0.293165 0.744731 0.610277 -0.270071 0.744731 0.619911 -0.247157 0.744731 0.527169 -0.311681 0.790536 0.642632 -0.18 0.744731 0.648324 -0.158278 0.744731 0.583665 -0.185439 0.790536 0.576731 -0.205994 0.790536 0.653163 -0.136944 0.744731 0.660492 -0.0955295 0.744731 0.608485 -0.0692708 0.790536 0.610262 -0.0513011 0.790536 0.66635 -0.0367922 0.744731 0.667118 -0.0181563 0.744731 -0.0568968 -0.0015485 0.998379 -0.0625833 -1.35328e-16 0.99804 -0.180593 -1.156e-16 0.983558 0.611484 0.0337627 0.790536 0.241412 0.00657025 0.9704 0.190693 -2.26904e-17 0.98165 0.0991181 0.00269759 0.995072 0.603089 0.106468 0.790536 0.456353 0.0805631 0.886144 0.533881 0.111935 0.838118 0.537182 0.0948325 0.838118 0.441654 0.14032 0.886144 0.51988 0.165174 0.838118 0.446235 0.124989 0.886144 0.513704 0.183482 0.838118 0.436408 0.155874 0.886144 0.550161 0.269026 0.790536 0.416302 0.20357 0.886144 0.480295 0.258601 0.838118 0.490038 0.239626 0.838118 0.457792 0.296622 0.838118 0.388908 0.25199 0.886144 0.444962 0.315542 0.838118 0.483926 0.375324 0.790536 0.431041 0.334308 0.838118 0.416005 0.352842 0.838118 0.276762 0.23474 0.931826 0.34448 0.422956 0.838118 0.323763 0.439016 0.838118 0.338995 0.510034 0.790536 0.255179 0.482122 0.838118 0.230328 0.494476 0.838118 0.204588 0.50567 0.838118 0.178038 0.515617 0.838118 0.150767 0.52424 0.838118 0.0802525 0.456408 0.886144 0.104386 0.4515 0.886144 0.106057 0.603162 0.790536 0.0365688 0.544262 0.838118 0.00732169 0.54544 0.838118 -0.0219572 0.545047 0.838118 -0.0511411 0.543086 0.838118 -0.0801054 0.539575 0.838118 -0.108728 0.534543 0.838118 -0.139736 0.441839 0.886144 -0.116294 0.44858 0.886144 -0.184667 0.583909 0.790536 -0.217564 0.500224 0.838118 -0.242869 0.488439 0.838118 -0.246908 0.392154 0.886144 -0.29064 0.461613 0.838118 -0.227036 0.403984 0.886144 -0.312991 0.44676 0.838118 -0.334261 0.431077 0.838118 -0.354418 0.414663 0.838118 -0.373444 0.397615 0.838118 -0.391326 0.380029 0.838118 -0.408064 0.361997 0.838118 -0.475643 0.385766 0.790536 -0.451512 0.306097 0.838118 -0.463806 0.287127 0.838118 -0.533338 0.301003 0.790536 -0.485288 0.249104 0.838118 -0.494549 0.230172 0.838118 -0.564573 0.237296 0.790536 -0.572919 0.21637 0.790536 -0.527689 0.138212 0.838118 -0.444026 0.132625 0.886144 -0.448288 0.117416 0.886144 -0.592431 0.15517 0.790536 -0.597257 0.135411 0.790536 -0.601325 0.116019 0.790536 -0.604682 0.097015 0.790536 -0.607374 0.0784151 0.790536 -0.609446 0.0602326 0.790536 -0.61094 0.0424777 0.790536 -0.611898 0.0251571 0.790536 -0.612359 0.00827553 0.790536 -0.612359 -0.00827542 0.790536 -0.611898 -0.0251572 0.790536 -0.61094 -0.0424777 0.790536 -0.609446 -0.0602326 0.790536 -0.607374 -0.078415 0.790536 -0.604682 -0.097015 0.790536 -0.597257 -0.135411 0.790536 -0.592431 -0.15517 0.790536 -0.586799 -0.17527 0.790536 -0.494549 -0.230172 0.838118 -0.427208 -0.17956 0.886144 -0.420135 -0.195538 0.886144 -0.555225 -0.258412 0.790536 -0.544829 -0.279667 0.790536 -0.520711 -0.322355 0.790536 -0.359916 -0.291906 0.886144 -0.423664 -0.343609 0.838118 -0.372213 -0.276054 0.886144 -0.408064 -0.361997 0.838118 -0.317252 -0.337786 0.886144 -0.373444 -0.397615 0.838118 -0.332444 -0.322846 0.886144 -0.354418 -0.414663 0.838118 -0.334261 -0.431077 0.838118 -0.246908 -0.392154 0.886144 -0.29064 -0.461613 0.838118 -0.265896 -0.379536 0.886144 -0.267248 -0.475538 0.838118 -0.242869 -0.488439 0.838118 -0.217564 -0.500224 0.838118 -0.191409 -0.510804 0.838118 -0.164487 -0.520098 0.838118 -0.0923677 -0.454111 0.886144 -0.108728 -0.534543 0.838118 -0.116294 -0.44858 0.886144 -0.068052 -0.458386 0.886144 -0.0899336 -0.605776 0.790536 -0.0219571 -0.545047 0.838118 0.0073216 -0.54544 0.838118 0.0365686 -0.544262 0.838118 0.0656584 -0.541523 0.838118 0.0944669 -0.537247 0.838118 0.122874 -0.531469 0.838118 0.151248 -0.438032 0.886144 0.178038 -0.515617 0.838118 0.128081 -0.445358 0.886144 0.204588 -0.50567 0.838118 0.230328 -0.494476 0.838118 0.255179 -0.482122 0.838118 0.0588513 -0.0798011 0.995072 0.062617 -0.0768816 0.995072 0.363486 -0.492879 0.790536 0.386745 -0.474848 0.790536 0.448894 -0.416588 0.790536 0.467045 -0.396132 0.790536 0.324969 -0.330368 0.886144 0.382528 -0.388883 0.838118 0.309292 -0.34509 0.886144 0.499555 -0.354256 0.790536 0.364074 -0.406212 0.838118 0.513958 -0.333015 0.790536 0.539223 -0.290329 0.790536 0.550161 -0.269026 0.790536 0.560027 -0.247833 0.790536 0.568868 -0.226806 0.790536 0.589719 -0.165179 0.790536 0.594942 -0.145246 0.790536 0.51988 -0.165174 0.838118 0.513704 -0.183482 0.838118 0.603089 -0.106468 0.790536 0.606108 -0.0876637 0.790536 0.537182 -0.0948325 0.838118 0.599383 -0.125668 0.790536 0.541988 -0.0617007 0.838118 0.543571 -0.0456948 0.838118 0.612188 -0.0166613 0.790536 0.611484 -0.0337627 0.790536 0.544659 0.030073 0.838118 0.543571 0.0456948 0.838118 0.0988063 0.00830606 0.995072 0.0985185 0.0112155 0.995072 0.239952 0.0273165 0.9704 0.450188 0.109906 0.886144 0.453548 0.0950919 0.886144 0.355182 0.0744683 0.931826 0.525273 0.147128 0.838118 0.430458 0.171623 0.886144 0.341759 0.122068 0.931826 0.3371 0.134401 0.931826 0.398904 0.235847 0.886144 0.408026 0.21969 0.886144 0.319533 0.172043 0.931826 0.378009 0.268063 0.886144 0.296026 0.209925 0.931826 0.366183 0.284005 0.886144 0.309292 0.34509 0.886144 0.292646 0.359314 0.886144 0.200881 0.302236 0.931826 0.256515 0.385939 0.886144 0.215395 0.29207 0.931826 0.23708 0.398173 0.886144 0.216782 0.409578 0.886144 0.195671 0.420073 0.886144 0.173804 0.429582 0.886144 0.151249 0.438032 0.886144 0.0817464 0.353578 0.931826 0.100303 0.348768 0.931826 0.122874 0.531469 0.838118 0.0557789 0.46004 0.886144 0.0310664 0.462367 0.886144 0.00622 0.463368 0.886144 -0.0186533 0.463034 0.886144 -0.043446 0.461368 0.886144 -0.068052 0.458386 0.886144 -0.0923678 0.454111 0.886144 -0.136892 0.528033 0.838118 -0.162608 0.433944 0.886144 -0.184828 0.424955 0.886144 -0.206325 0.414944 0.886144 -0.267249 0.475538 0.838118 -0.265896 0.379536 0.886144 -0.235789 0.275869 0.931826 -0.301089 0.352269 0.886144 -0.222378 0.286789 0.931826 -0.317252 0.337786 0.886144 -0.332444 0.322846 0.886144 -0.346663 0.307527 0.886144 -0.359915 0.291906 0.886144 -0.372213 0.276054 0.886144 -0.383573 0.260038 0.886144 -0.394018 0.243923 0.886144 -0.475053 0.268109 0.838118 -0.412268 0.211622 0.886144 -0.420135 0.195538 0.886144 -0.502875 0.211364 0.838118 -0.510309 0.192725 0.838118 -0.516893 0.174297 0.838118 -0.522672 0.156116 0.838118 -0.531987 0.120613 0.838118 -0.535611 0.10334 0.838118 -0.538601 0.086413 0.838118 -0.540999 0.0698457 0.838118 -0.542844 0.0536502 0.838118 -0.544175 0.0378356 0.838118 -0.545028 0.0224079 0.838118 -0.545439 0.00737116 0.838118 -0.545439 -0.00737106 0.838118 -0.545028 -0.022408 0.838118 -0.544175 -0.0378356 0.838118 -0.542844 -0.0536502 0.838118 -0.540999 -0.0698456 0.838118 -0.457558 -0.0734105 0.886144 -0.455018 -0.0877908 0.886144 -0.531987 -0.120613 0.838118 -0.527689 -0.138212 0.838118 -0.444026 -0.132625 0.886144 -0.439117 -0.148071 0.886144 -0.510309 -0.192725 0.838118 -0.502875 -0.211364 0.838118 -0.412268 -0.211622 0.886144 -0.403573 -0.227767 0.886144 -0.394018 -0.243923 0.886144 -0.383573 -0.260038 0.886144 -0.43814 -0.324949 0.838118 -0.346663 -0.307528 0.886144 -0.391326 -0.380029 0.838118 -0.301089 -0.352269 0.886144 -0.283965 -0.366213 0.886144 -0.312991 -0.44676 0.838118 -0.227036 -0.403984 0.886144 -0.206325 -0.414944 0.886144 -0.184828 -0.424955 0.886144 -0.162608 -0.433944 0.886144 -0.0910719 -0.351292 0.931826 -0.10943 -0.346013 0.931826 -0.136892 -0.528033 0.838118 -0.043446 -0.461368 0.886144 -0.0186532 -0.463034 0.886144 0.00621993 -0.463368 0.886144 0.0310662 -0.462367 0.886144 0.0557788 -0.46004 0.886144 0.0802526 -0.456408 0.886144 0.100303 -0.348768 0.931826 0.0817464 -0.353578 0.931826 0.150767 -0.52424 0.838118 0.173804 -0.429582 0.886144 0.195671 -0.420073 0.886144 0.185662 -0.311817 0.931826 0.169766 -0.320748 0.931826 0.34448 -0.422955 0.838118 0.399838 -0.371063 0.838118 0.444962 -0.315542 0.838118 0.341759 -0.122068 0.931826 0.22743 -0.0812322 0.9704 0.345868 -0.109887 0.931826 0.457792 -0.296622 0.838118 0.490038 -0.239626 0.838118 0.498826 -0.220749 0.838118 0.506701 -0.20202 0.838118 0.525273 -0.147128 0.838118 0.529925 -0.129373 0.838118 0.436408 -0.155874 0.886144 0.441654 -0.14032 0.886144 0.533881 -0.111935 0.838118 0.539871 -0.0780836 0.838118 0.456353 -0.0805632 0.886144 0.460435 -0.0524167 0.886144 0.461781 -0.0388191 0.886144 0.545287 -0.0148405 0.838118 0.544659 -0.0300731 0.838118 0.392677 5.22397e-17 0.919676 0.362771 0.00987314 0.931826 0.462705 0.025548 0.886144 0.461781 0.0388192 0.886144 0.460435 0.0524167 0.886144 0.458637 0.0663343 0.886144 0.0981337 0.0141934 0.995072 0.239014 0.0345695 0.9704 0.349456 0.0978816 0.931826 0.352551 0.0860698 0.931826 0.234611 0.0572767 0.9704 0.230164 0.0731265 0.9704 0.345868 0.109887 0.931826 0.232551 0.065137 0.9704 0.423768 0.187533 0.886144 0.331861 0.146861 0.931826 0.304561 0.197338 0.931826 0.31239 0.184696 0.931826 0.207885 0.122909 0.9704 0.190833 0.148006 0.9704 0.242212 0.270246 0.931826 0.229177 0.281385 0.931826 0.275047 0.372958 0.886144 0.185662 0.311817 0.931826 0.169766 0.320748 0.931826 0.153233 0.328967 0.931826 0.136109 0.336414 0.931826 0.0667483 0.232094 0.9704 0.0788218 0.228276 0.9704 0.128081 0.445358 0.886144 0.0628473 0.357422 0.931826 0.0436815 0.360266 0.931826 0.0243287 0.362088 0.931826 0.004871 0.362872 0.931826 -0.0146078 0.362611 0.931826 -0.0340234 0.361307 0.931826 -0.0532928 0.358971 0.931826 -0.0606055 0.233773 0.9704 -0.091072 0.351292 0.931826 -0.0481366 0.236656 0.9704 -0.10943 0.346013 0.931826 -0.127341 0.33983 0.931826 -0.144742 0.332791 0.931826 -0.118318 0.210532 0.9704 -0.177796 0.316368 0.931826 -0.107524 0.216244 0.9704 -0.193358 0.307103 0.931826 -0.208228 0.297222 0.931826 -0.283965 0.366214 0.886144 -0.248446 0.264527 0.931826 -0.260343 0.252827 0.931826 -0.271478 0.240831 0.931826 -0.281857 0.228597 0.931826 -0.291487 0.216183 0.931826 -0.210318 0.118698 0.9704 -0.316045 0.178368 0.931826 -0.205338 0.127118 0.9704 -0.403573 0.227767 0.886144 -0.334555 0.140617 0.931826 -0.218949 0.101903 0.9704 -0.222635 0.093576 0.9704 -0.427208 0.17956 0.886144 -0.433523 0.163726 0.886144 -0.439117 0.148071 0.886144 -0.347725 0.103861 0.931826 -0.351063 0.0919504 0.931826 -0.45194 0.102464 0.886144 -0.455018 0.0877908 0.886144 -0.457558 0.0734105 0.886144 -0.459595 0.0593361 0.886144 -0.461163 0.0455775 0.886144 -0.462293 0.0321425 0.886144 -0.463018 0.0190362 0.886144 -0.463367 0.00626203 0.886144 -0.463367 -0.00626194 0.886144 -0.463018 -0.0190363 0.886144 -0.462293 -0.0321425 0.886144 -0.461163 -0.0455775 0.886144 -0.459595 -0.059336 0.886144 -0.353923 -0.0802418 0.931826 -0.237128 -0.0457514 0.9704 -0.235524 -0.0533984 0.9704 -0.45194 -0.102464 0.886144 -0.448288 -0.117416 0.886144 -0.347725 -0.103861 0.931826 -0.343881 -0.115957 0.931826 -0.433523 -0.163726 0.886144 -0.334555 -0.140617 0.931826 -0.329015 -0.15313 0.931826 -0.322854 -0.165725 0.931826 -0.316045 -0.178368 0.931826 -0.308563 -0.191021 0.931826 -0.300383 -0.203641 0.931826 -0.281857 -0.228597 0.931826 -0.291487 -0.216183 0.931826 -0.271478 -0.240831 0.931826 -0.248446 -0.264527 0.931826 -0.260343 -0.252827 0.931826 -0.235789 -0.275869 0.931826 -0.138569 -0.197792 0.9704 -0.208228 -0.297222 0.931826 -0.147986 -0.190849 0.9704 -0.193358 -0.307103 0.931826 -0.177796 -0.316368 0.931826 -0.161577 -0.324951 0.931826 -0.144742 -0.332791 0.931826 -0.0728223 -0.23026 0.9704 -0.0847415 -0.226146 0.9704 -0.139736 -0.441839 0.886144 -0.0723349 -0.355623 0.931826 -0.0532928 -0.35897 0.931826 -0.0340234 -0.361307 0.931826 -0.0146077 -0.362611 0.931826 0.00487095 -0.362872 0.931826 0.0243285 -0.362088 0.931826 0.0436815 -0.360266 0.931826 0.0543996 -0.235295 0.9704 0.0418229 -0.237852 0.9704 0.104386 -0.4515 0.886144 0.118446 -0.343031 0.931826 0.136109 -0.336414 0.931826 0.153234 -0.328967 0.931826 0.216782 -0.409578 0.886144 0.292647 -0.359314 0.886144 0.339675 -0.315229 0.886144 -0.0489951 0.0289677 0.998379 0.366183 -0.284004 0.886144 0.378009 -0.268063 0.886144 0.25449 -0.258718 0.931826 0.242212 -0.270246 0.931826 0.388908 -0.25199 0.886144 0.408026 -0.21969 0.886144 0.416302 -0.20357 0.886144 0.423768 -0.187533 0.886144 0.430458 -0.171623 0.886144 0.31239 -0.184696 0.931826 0.446235 -0.12499 0.886144 0.450188 -0.109906 0.886144 0.453548 -0.0950919 0.886144 0.458637 -0.0663344 0.886144 0.357379 -0.0630906 0.931826 0.360576 -0.0410485 0.931826 0.361629 -0.0304 0.931826 0.463238 -0.0126075 0.886144 0.462705 -0.025548 0.886144 0.299582 -9.43661e-17 0.95407 0.362353 0.0200071 0.931826 0.361629 0.0304 0.931826 0.360576 0.0410486 0.931826 0.359168 0.0519477 0.931826 0.357379 0.0630905 0.931826 0.0976449 0.0172379 0.995072 0.236362 0.0495562 0.9704 0.237824 0.0419847 0.9704 0.0933773 0.033352 0.995072 0.22743 0.0812322 0.9704 0.0944999 0.030024 0.995072 0.224329 0.0894395 0.9704 0.0921042 0.0367217 0.995072 0.326014 0.159419 0.931826 0.216952 0.106088 0.9704 0.202676 0.131322 0.9704 0.286765 0.222409 0.931826 0.169355 0.172168 0.9704 0.161184 0.17984 0.9704 0.0588513 0.0798011 0.995072 0.143338 0.194363 0.9704 0.062617 0.0768817 0.995072 0.13368 0.201128 0.9704 0.123552 0.207504 0.9704 0.112974 0.213448 0.9704 0.101972 0.218917 0.9704 0.0323623 0.0937247 0.995072 0.0371884 0.0919168 0.995072 0.118446 0.343031 0.931826 0.0543996 0.235295 0.9704 0.0418228 0.237852 0.9704 0.0290686 0.239746 0.9704 0.0161899 0.240958 0.9704 0.0032415 0.24148 0.9704 -0.009721 0.241306 0.9704 -0.0226414 0.240438 0.9704 -0.0197637 0.097165 0.995072 -0.014561 0.0980799 0.995072 -0.072335 0.355623 0.931826 -0.0728223 0.230261 0.9704 -0.0847414 0.226146 0.9704 -0.0963212 0.221461 0.9704 -0.161577 0.324951 0.931826 -0.128674 0.204367 0.9704 -0.138569 0.197792 0.9704 -0.15691 0.183582 0.9704 -0.147986 0.190849 0.9704 -0.0711323 0.0690787 0.995072 -0.17325 0.168248 0.9704 -0.0678818 0.0722755 0.995072 -0.18066 0.160265 0.9704 -0.187567 0.152124 0.9704 -0.193975 0.143863 0.9704 -0.300383 0.203641 0.931826 -0.308563 0.191021 0.931826 -0.322855 0.165725 0.931826 -0.329015 0.15313 0.931826 -0.3395 0.128217 0.931826 -0.343881 0.115957 0.931826 -0.0973593 0.0187844 0.995072 0.0555089 -0.0125851 0.998379 0.0558872 -0.0107828 0.998379 -0.353923 0.0802419 0.931826 -0.356333 0.0687507 0.931826 -0.358322 0.0574891 0.931826 -0.359918 0.0464672 0.931826 -0.361145 0.0356926 0.931826 -0.362031 0.0251714 0.931826 -0.362599 0.0149076 0.931826 -0.362872 0.00490391 0.931826 -0.362872 -0.00490385 0.931826 -0.362599 -0.0149077 0.931826 -0.362031 -0.0251714 0.931826 -0.361145 -0.0356926 0.931826 -0.359918 -0.0464671 0.931826 -0.358322 -0.0574892 0.931826 -0.356333 -0.0687507 0.931826 -0.351063 -0.0919504 0.931826 -0.0927601 -0.0350321 0.995072 -0.225926 -0.0853241 0.9704 -0.0939569 -0.0316824 0.995072 -0.3395 -0.128217 0.931826 -0.222635 -0.0935759 0.9704 -0.218949 -0.101903 0.9704 -0.214849 -0.110285 0.9704 -0.210318 -0.118698 0.9704 -0.205339 -0.127118 0.9704 -0.199896 -0.135517 0.9704 -0.187567 -0.152124 0.9704 -0.193975 -0.143863 0.9704 -0.0711323 -0.0690787 0.995072 -0.17325 -0.168248 0.9704 -0.0741748 -0.0658011 0.995072 -0.165333 -0.176034 0.9704 -0.15691 -0.183582 0.9704 -0.222378 -0.286789 0.931826 -0.128674 -0.204368 0.9704 -0.118318 -0.210533 0.9704 -0.107524 -0.216244 0.9704 -0.0347929 -0.0928501 0.995072 -0.0395472 -0.0909269 0.995072 -0.127341 -0.33983 0.931826 -0.0606054 -0.233773 0.9704 -0.0481366 -0.236655 0.9704 -0.0354647 -0.238883 0.9704 -0.0226415 -0.240438 0.9704 -0.00972094 -0.241306 0.9704 0.00324146 -0.24148 0.9704 0.0161899 -0.240958 0.9704 0.0171715 -0.0976566 0.995072 0.0119349 -0.0984339 0.995072 0.0628473 -0.357422 0.931826 0.0667483 -0.232094 0.9704 0.0788217 -0.228276 0.9704 0.0905762 -0.223872 0.9704 0.101972 -0.218917 0.9704 0.123552 -0.207504 0.9704 0.112974 -0.213448 0.9704 0.13368 -0.201128 0.9704 0.266006 -0.246862 0.931826 0.276762 -0.23474 0.931826 0.286765 -0.222409 0.931826 0.296026 -0.209925 0.931826 0.169355 -0.172168 0.9704 0.161184 -0.17984 0.9704 0.304561 -0.197338 0.931826 0.319533 -0.172043 0.931826 0.326014 -0.159419 0.931826 0.331861 -0.146861 0.931826 0.3371 -0.134401 0.931826 0.207885 -0.122909 0.9704 0.349456 -0.0978817 0.931826 0.352551 -0.0860698 0.931826 0.230164 -0.0731265 0.9704 0.355182 -0.0744683 0.931826 0.359168 -0.0519477 0.931826 0.239952 -0.0273165 0.9704 0.240653 -0.0202302 0.9704 0.362353 -0.0200071 0.931826 0.36277 -0.00987317 0.931826 -0.521825 -6.66013e-17 0.853053 -0.525217 -0.0142943 0.850848 -0.452963 -1.43047e-16 0.891529 0.241134 0.0133141 0.9704 0.240653 0.0202302 0.9704 0.0963258 0.0235165 0.995072 0.0970448 0.0203466 0.995072 -0.0557064 -0.0116795 0.998379 0.0954801 0.0267437 0.995072 -0.0552939 -0.0134992 0.998379 0.220843 0.0977313 0.9704 0.0906729 0.0401262 0.995072 -0.0528706 -0.0210794 0.998379 -0.0520488 -0.0230336 0.998379 0.212639 0.114489 0.9704 0.0873044 0.0470065 0.995072 0.0853528 0.0504636 0.995072 -0.0489949 -0.0289675 0.998379 0.0832139 0.0539177 0.995072 0.196996 0.139698 0.9704 0.0808819 0.0573568 0.995072 0.0695331 0.0706883 0.995072 0.0661785 0.0738382 0.995072 0.15251 0.187253 0.9704 0.0548859 0.0825785 0.995072 0.0507275 0.0851963 0.995072 0.0463844 0.0876365 0.995072 -0.0213473 -0.052763 0.998379 -0.0240331 -0.0515951 0.998379 0.0905762 0.223873 0.9704 0.0274053 0.0952923 0.995072 0.0223352 0.0966065 0.995072 0.0171715 0.0976566 0.995072 0.0119349 0.0984339 0.995072 0.00664721 0.0989318 0.995072 0.00133088 0.0991459 0.995072 -0.00399121 0.0990745 0.995072 0.00835843 -0.0563008 0.998379 0.00533621 -0.0566672 0.998379 -0.0354647 0.238883 0.9704 -0.0248832 0.0959818 0.995072 -0.0298991 0.0945395 0.995072 -0.0347928 0.0928501 0.995072 -0.0395472 0.0909269 0.995072 -0.0485784 0.0864397 0.995072 -0.0441469 0.0887848 0.995072 -0.0528304 0.0839085 0.995072 0.0348777 -0.0449799 0.998379 -0.0607594 0.078358 0.995072 0.0326584 -0.0466162 0.998379 -0.0644234 0.0753742 0.995072 -0.165333 0.176034 0.9704 0.0442061 -0.035853 0.998379 -0.0770104 0.0624586 0.995072 0.0425784 -0.0377717 0.998379 0.0471119 -0.0319389 0.998379 -0.0820724 0.0556399 0.995072 0.0457166 -0.033906 0.998379 -0.199895 0.135517 0.9704 -0.0863516 0.0487348 0.995072 -0.0843072 0.0521918 0.995072 -0.214849 0.110285 0.9704 -0.0898952 0.0418389 0.995072 -0.0914088 0.0384201 0.995072 -0.225927 0.0853242 0.9704 -0.228842 0.0771656 0.9704 -0.2314 0.0691163 0.9704 -0.233621 0.06119 0.9704 -0.235524 0.0533984 0.9704 -0.237128 0.0457514 0.9704 -0.238452 0.0382572 0.9704 -0.239514 0.0309224 0.9704 -0.240331 0.0237523 0.9704 -0.24092 0.0167508 0.9704 -0.241298 0.00992053 0.9704 -0.241479 0.0032634 0.9704 -0.241479 -0.00326335 0.9704 -0.241298 -0.00992058 0.9704 -0.24092 -0.0167508 0.9704 -0.240331 -0.0237523 0.9704 -0.239514 -0.0309224 0.9704 -0.238452 -0.0382572 0.9704 -0.0973593 -0.0187844 0.995072 -0.0967006 -0.0219241 0.995072 -0.233621 -0.06119 0.9704 -0.2314 -0.0691163 0.9704 -0.228841 -0.0771657 0.9704 -0.0914088 -0.0384201 0.995072 -0.0898954 -0.041839 0.995072 0.0483949 0.0299597 0.998379 -0.0843072 -0.0521918 0.995072 0.0495685 0.0279752 0.998379 -0.0820724 -0.0556399 0.995072 -0.0770104 -0.0624586 0.995072 -0.0796417 -0.0590667 0.995072 -0.18066 -0.160265 0.9704 -0.0678818 -0.0722755 0.995072 0.0348778 0.0449799 0.998379 -0.0607594 -0.078358 0.995072 0.0369809 0.043267 0.998379 -0.0568932 -0.0812086 0.995072 -0.0528304 -0.0839085 0.995072 -0.0485784 -0.0864397 0.995072 0.0227012 0.0521946 0.998379 0.0253416 0.0509651 0.998379 -0.0963212 -0.221462 0.9704 -0.0298991 -0.0945395 0.995072 -0.0248832 -0.0959818 0.995072 -0.0197637 -0.0971652 0.995072 -0.014561 -0.0980799 0.995072 -0.00929606 -0.0987181 0.995072 -0.00399119 -0.0990745 0.995072 0.00133086 -0.0991457 0.995072 -0.00685096 0.0565038 0.998379 -0.00381568 0.0567898 0.998379 0.0290686 -0.239746 0.9704 0.0223352 -0.0966065 0.995072 0.0274053 -0.0952923 0.995072 0.0323623 -0.0937249 0.995072 -0.0266261 0.050306 0.998379 0.0463844 -0.0876365 0.995072 0.0507274 -0.0851961 0.995072 0.0548859 -0.0825786 0.995072 0.177018 -0.164279 0.9704 0.184176 -0.156212 0.9704 0.190833 -0.148006 0.9704 0.196996 -0.139698 0.9704 0.0695331 -0.0706883 0.995072 0.0661785 -0.0738382 0.995072 0.202676 -0.131322 0.9704 0.212639 -0.114489 0.9704 0.216952 -0.106088 0.9704 0.220843 -0.0977313 0.9704 0.224329 -0.0894395 0.9704 0.0853528 -0.0504636 0.995072 -0.0542458 0.0172347 0.998379 0.0944999 -0.030024 0.995072 -0.0536012 0.019145 0.998379 0.232551 -0.0651371 0.9704 0.234611 -0.0572767 0.9704 0.0933773 -0.033352 0.995072 0.237824 -0.0419848 0.9704 0.236362 -0.0495563 0.9704 0.239015 -0.0345696 0.9704 0.0976449 -0.0172379 0.995072 0.0985185 -0.0112155 0.995072 0.0988063 -0.00830606 0.995072 0.241412 -0.00657028 0.9704 0.241134 -0.0133141 0.9704 0.0673443 -2.16811e-16 0.99773 0.099004 0.00546645 0.995072 -0.432487 -0.0117705 0.901563 -0.324982 -0.00884468 0.945679 -0.374419 2.49651e-17 0.92726 -0.198976 -0.0226518 0.979743 -0.32396 -0.0272334 0.945679 -0.323016 -0.0367727 0.945679 -0.321754 -0.0465364 0.945679 -0.198199 -0.0286662 0.979743 -0.19284 -0.0540139 0.979743 -0.19086 -0.060639 0.979743 -0.0542458 -0.0172347 0.998379 -0.188593 -0.0673605 0.979743 -0.0536014 -0.0191451 0.998379 0.0890754 0.0435574 0.995072 -0.0501152 -0.0269831 0.998379 -0.0511318 -0.0250032 0.998379 -0.179904 -0.0879721 0.979743 -0.0477671 -0.0309503 0.998379 -0.168066 -0.108897 0.979743 -0.0399141 -0.0405772 0.998379 -0.0379883 -0.0423852 0.998379 -0.13366 -0.14913 0.979743 -0.0359439 -0.0441322 0.998379 -0.0337823 -0.045808 0.998379 -0.0315061 -0.0474024 0.998379 -0.029119 -0.048905 0.998379 -0.0266261 -0.050306 0.998379 -0.0936819 -0.176998 0.979743 0.0418673 0.0898822 0.995072 -0.018577 -0.0538009 0.998379 -0.0157315 -0.0547007 0.998379 -0.012821 -0.0554549 0.998379 -0.0098569 -0.0560577 0.998379 -0.00685097 -0.0565038 0.998379 -0.00381569 -0.0567896 0.998379 -0.000763964 -0.0569125 0.998379 -0.00268796 -0.200243 0.979743 0.00229108 -0.0568717 0.998379 0.00806099 -0.200099 0.979743 -0.00929605 0.0987181 0.995072 0.011345 -0.0557758 0.998379 0.0142837 -0.0550965 0.998379 0.0171629 -0.0542683 0.998379 0.0199721 -0.0532986 0.998379 0.0227012 -0.0521946 0.998379 0.0798728 -0.183644 0.979743 0.0253415 -0.0509649 0.998379 0.0278854 -0.0496188 0.998379 0.0303262 -0.048166 0.998379 -0.0568932 0.0812087 0.995072 0.0369811 -0.0432671 0.998379 0.0408319 -0.0396531 0.998379 0.0389662 -0.0414883 0.998379 -0.0741748 0.0658011 0.995072 -0.0796417 0.0590667 0.995072 0.0495685 -0.0279752 0.998379 0.0483949 -0.0299597 0.998379 -0.0882121 0.0452803 0.995072 0.0516027 -0.0240168 0.998379 0.0524714 -0.0220543 0.998379 -0.0927601 0.0350321 0.995072 -0.0939569 0.0316824 0.995072 -0.0950073 0.0283775 0.995072 -0.0959193 0.0251232 0.995072 -0.0967006 0.0219241 0.995072 -0.0979028 0.0157075 0.995072 -0.0983386 0.012696 0.995072 -0.0986741 0.00975213 0.995072 -0.098916 0.00687747 0.995072 -0.0990711 0.00407313 0.995072 -0.0991458 0.00133987 0.995072 -0.0991458 -0.00133986 0.995072 -0.0990711 -0.00407316 0.995072 -0.098916 -0.00687747 0.995072 -0.0986741 -0.00975213 0.995072 -0.0983387 -0.012696 0.995072 -0.0979028 -0.0157075 0.995072 0.0555091 0.0125851 0.998379 0.195305 0.0442798 0.979743 0.0550603 0.0144214 0.998379 -0.0959193 -0.0251232 0.995072 -0.0950073 -0.0283775 0.995072 0.0532469 0.0201094 0.998379 0.0539339 0.0181866 0.998379 0.0516027 0.0240168 0.998379 0.18156 0.0845015 0.979743 0.0506364 0.0259923 0.998379 -0.0882121 -0.0452804 0.995072 -0.0863516 -0.0487348 0.995072 0.047112 0.031939 0.998379 0.16576 0.112375 0.979743 0.0457168 0.0339061 0.998379 0.0442061 0.035853 0.998379 0.0408319 0.0396531 0.998379 0.0425784 0.0377717 0.998379 0.0389661 0.0414881 0.998379 -0.0644235 -0.0753743 0.995072 0.0326584 0.0466162 0.998379 0.0303262 0.048166 0.998379 0.0278855 0.049619 0.998379 -0.0441469 -0.0887848 0.995072 0.0199721 0.0532986 0.998379 0.0171629 0.0542683 0.998379 0.0142836 0.0550963 0.998379 0.0113449 0.0557755 0.998379 0.00835843 0.0563008 0.998379 0.00533622 0.0566672 0.998379 0.00229106 0.0568717 0.998379 -0.000763958 0.0569128 0.998379 -0.00268793 0.200243 0.979743 0.00664717 -0.0989318 0.995072 -0.00985692 0.0560577 0.998379 -0.012821 0.0554549 0.998379 -0.0157314 0.0547005 0.998379 -0.0185769 0.0538007 0.998379 -0.0291191 0.0489052 0.998379 -0.0315062 0.0474026 0.998379 -0.110852 0.166783 0.979743 -0.0337823 0.045808 0.998379 0.0726795 -0.067449 0.995072 0.0756184 -0.0641369 0.995072 0.0783514 -0.0607679 0.995072 0.0808819 -0.0573568 0.995072 0.0832139 -0.0539177 0.995072 0.0873044 -0.0470066 0.995072 0.0890754 -0.0435574 0.995072 0.0906729 -0.0401262 0.995072 0.0921042 -0.0367217 0.995072 0.0954801 -0.0267438 0.995072 0.0963258 -0.0235165 0.995072 0.0970446 -0.0203466 0.995072 0.0981337 -0.0141934 0.995072 -0.0560512 0.0098951 0.998379 -0.0565524 0.00643801 0.998379 -0.0567176 0.00476791 0.998379 0.0991181 -0.0026976 0.995072 0.099004 -0.00546645 0.995072 -0.200187 -0.00544828 0.979743 -0.0568311 -0.0031379 0.998379 -0.0567176 -0.00476791 0.998379 -0.0565524 -0.00643802 0.998379 -0.0563315 -0.00814742 0.998379 -0.0560509 -0.00989506 0.998379 -0.320152 -0.0565186 0.945679 -0.196 -0.0410937 0.979743 -0.197212 -0.0348152 0.979743 -0.194548 -0.0474958 0.979743 -0.318184 -0.0667112 0.945679 -0.0548085 -0.0153517 0.998379 -0.186021 -0.0741663 0.979743 -0.306159 -0.109352 0.945679 -0.301985 -0.120401 0.945679 -0.172386 -0.101921 0.979743 -0.176327 -0.0949383 0.979743 -0.286248 -0.154122 0.945679 -0.14679 -0.136226 0.979743 -0.126466 -0.155276 0.979743 -0.118861 -0.161173 0.979743 -0.102453 -0.172069 0.979743 -0.166322 -0.279336 0.945679 -0.0845586 -0.181534 0.979743 -0.0751089 -0.185643 0.979743 -0.0653617 -0.189295 0.979743 -0.05535 -0.19246 0.979743 -0.04511 -0.195115 0.979743 -0.0346809 -0.197235 0.979743 -0.0134253 -0.199811 0.979743 -0.0217944 -0.324371 0.945679 0.0187751 -0.199379 0.979743 0.0294085 -0.19809 0.979743 0.0399165 -0.196243 0.979743 0.0502562 -0.193853 0.979743 0.0702704 -0.187528 0.979743 0.114076 -0.304431 0.945679 0.0891627 -0.179317 0.979743 0.098113 -0.174581 0.979743 0.114906 -0.164016 0.979743 0.122715 -0.158258 0.979743 0.1371 -0.145974 0.979743 0.149809 -0.132897 0.979743 0.160851 -0.119296 0.979743 0.17816 -0.0914519 0.979743 0.174403 -0.0984288 0.979743 0.283124 -0.159788 0.945679 0.0506364 -0.0259923 0.998379 0.184617 -0.0775964 0.979743 0.299705 -0.125969 0.945679 0.187346 -0.0707537 0.979743 0.0532469 -0.0201094 0.998379 0.0539339 -0.0181866 0.998379 0.0545369 -0.0162895 0.998379 0.0550603 -0.0144214 0.998379 0.0561992 -0.00901658 0.998379 0.196635 -0.0379386 0.979743 0.0564494 -0.0072879 0.998379 0.0566419 -0.00559802 0.998379 0.0567808 -0.00394788 0.998379 0.0568696 -0.00233809 0.998379 0.0569125 -0.000769125 0.998379 0.0569125 0.000769115 0.998379 0.0568696 0.00233811 0.998379 0.0567806 0.00394786 0.998379 0.0566417 0.005598 0.998379 0.0564494 0.00728789 0.998379 0.0561992 0.00901658 0.998379 0.0558872 0.0107828 0.998379 0.0545369 0.0162895 0.998379 0.189763 0.0639884 0.979743 0.0524712 0.0220542 0.998379 0.174403 0.0984288 0.979743 0.149809 0.132897 0.979743 0.155537 0.126147 0.979743 0.252497 0.204785 0.945679 0.130115 0.152232 0.979743 0.1371 0.145974 0.979743 0.222566 0.236972 0.945679 0.122715 0.158258 0.979743 0.114906 0.164016 0.979743 0.0891627 0.179317 0.979743 0.098113 0.174581 0.979743 0.159276 0.283413 0.945679 0.0798728 0.183644 0.979743 0.0702705 0.187528 0.979743 0.0603868 0.19094 0.979743 0.0502561 0.193853 0.979743 0.0399165 0.196243 0.979743 0.00806094 0.200099 0.979743 0.0187751 0.199379 0.979743 0.0304793 0.32367 0.945679 0.013086 0.324839 0.945679 -0.0134252 0.199811 0.979743 -0.0241047 0.198805 0.979743 -0.0346809 0.197235 0.979743 -0.04511 0.195115 0.979743 -0.05535 0.19246 0.979743 -0.0936819 0.176998 0.979743 -0.118861 0.161173 0.979743 -0.0417201 0.0387176 0.998379 -0.0434072 0.0368165 0.998379 -0.0449761 0.0348826 0.998379 -0.0464286 0.0329246 0.998379 -0.0477673 0.0309504 0.998379 -0.0511318 0.0250032 0.998379 -0.0520488 0.0230336 0.998379 -0.0528704 0.0210793 0.998379 -0.0552939 0.0134992 0.998379 -0.0548085 0.0153517 0.998379 -0.19284 0.0540139 0.979743 -0.19086 0.060639 0.979743 -0.188593 0.0673606 0.979743 -0.0557067 0.0116796 0.998379 -0.0563315 0.00814743 0.998379 -0.197212 0.0348152 0.979743 -0.0568311 0.0031379 0.998379 -0.0568966 0.0015485 0.998379 -0.284229 -1.77307e-16 0.958757 -0.199957 -0.0110405 0.979743 -0.199557 -0.0167756 0.979743 -0.315827 -0.0771042 0.945679 -0.412336 -0.131005 0.901563 -0.30984 -0.0984407 0.945679 -0.416613 -0.116692 0.901563 -0.183131 -0.0810422 0.979743 -0.297292 -0.131563 0.945679 -0.401883 -0.16023 0.901563 -0.395637 -0.175085 0.901563 -0.272836 -0.176782 0.945679 -0.279849 -0.165457 0.945679 -0.372424 -0.22019 0.901563 -0.247932 -0.210288 0.945679 -0.238297 -0.221147 0.945679 -0.140435 -0.142768 0.979743 -0.216982 -0.242096 0.945679 -0.205304 -0.252074 0.945679 -0.192958 -0.261646 0.945679 -0.110852 -0.166783 0.979743 -0.152082 -0.287337 0.945679 -0.137272 -0.2947 0.945679 -0.121931 -0.301371 0.945679 -0.106108 -0.307299 0.945679 -0.0898546 -0.312438 0.945679 -0.0391314 -0.322739 0.945679 -0.0563007 -0.32019 0.945679 -0.0749251 -0.42611 0.901563 -0.0520761 -0.429502 0.901563 -0.0241047 -0.198805 0.979743 -0.00436361 -0.325073 0.945679 0.0130861 -0.324839 0.945679 0.0304793 -0.32367 0.945679 0.0477415 -0.321578 0.945679 0.0648001 -0.318579 0.945679 0.0815853 -0.314699 0.945679 0.0603868 -0.19094 0.979743 0.129665 -0.298125 0.945679 0.144746 -0.291102 0.945679 0.186538 -0.266262 0.945679 0.173217 -0.275114 0.945679 0.230517 -0.366122 0.901563 0.106701 -0.169469 0.979743 0.222566 -0.236972 0.945679 0.211228 -0.247132 0.945679 0.281102 -0.328884 0.901563 0.130115 -0.152232 0.979743 0.143665 -0.139517 0.979743 0.243199 -0.215744 0.945679 0.155537 -0.126147 0.979743 0.261124 -0.193664 0.945679 0.16576 -0.112375 0.979743 0.170274 -0.105411 0.979743 0.18156 -0.0845015 0.979743 0.189763 -0.0639883 0.979743 0.191885 -0.0573136 0.979743 0.193727 -0.0507409 0.979743 0.195305 -0.0442798 0.979743 0.19929 -0.0196962 0.979743 0.198613 -0.0256419 0.979743 0.322426 -0.0416269 0.945679 0.197733 -0.0317242 0.979743 0.200092 -0.00822644 0.979743 0.200243 -0.00270612 0.979743 0.601155 0.0776121 0.795355 0.671723 0.0867228 0.735709 0.59849 0.0960217 0.795355 0.200243 0.00270608 0.979743 0.200092 0.00822648 0.979743 0.199779 0.0138903 0.979743 0.199779 -0.0138903 0.979743 0.19929 0.0196962 0.979743 0.198613 0.0256419 0.979743 0.197733 0.0317242 0.979743 0.196635 0.0379386 0.979743 0.317056 0.0718833 0.945679 0.193727 0.0507409 0.979743 0.191885 0.0573137 0.979743 0.299705 0.125969 0.945679 0.304136 0.114861 0.945679 0.404745 0.152857 0.901563 0.187346 0.0707537 0.979743 0.184617 0.0775964 0.979743 0.294743 0.137179 0.945679 0.17816 0.091452 0.979743 0.283124 0.159788 0.945679 0.170274 0.105411 0.979743 0.269093 0.182428 0.945679 0.160851 0.119296 0.979743 0.243199 0.215744 0.945679 0.143665 0.139517 0.979743 0.211227 0.247132 0.945679 0.199214 0.256915 0.945679 0.173217 0.275113 0.945679 0.230517 0.366122 0.901563 0.106701 0.169469 0.979743 0.144746 0.291102 0.945679 0.129665 0.298125 0.945679 0.114076 0.304431 0.945679 0.0980313 0.30997 0.945679 0.0815853 0.314699 0.945679 0.0477415 0.321578 0.945679 0.0635345 0.427956 0.901563 0.0294085 0.19809 0.979743 -0.00436355 0.325073 0.945679 -0.0217943 0.324371 0.945679 -0.0391313 0.322739 0.945679 -0.0563007 0.32019 0.945679 -0.0732311 0.316747 0.945679 -0.121931 0.301371 0.945679 -0.106107 0.307299 0.945679 -0.141208 0.408954 0.901563 -0.0653617 0.189295 0.979743 -0.137272 0.2947 0.945679 -0.152082 0.287337 0.945679 -0.102453 0.172069 0.979743 -0.179956 0.270753 0.945679 -0.192958 0.261646 0.945679 -0.385122 0.357405 0.850848 -0.400694 0.339855 0.850848 -0.14679 0.136226 0.979743 -0.152725 0.129536 0.979743 -0.158245 0.122732 0.979743 -0.163356 0.115843 0.979743 -0.168066 0.108897 0.979743 -0.186021 0.0741663 0.979743 -0.297292 0.131563 0.945679 -0.301985 0.120401 0.945679 -0.179904 0.0879721 0.979743 -0.183131 0.0810422 0.979743 -0.279849 0.165457 0.945679 -0.318184 0.0667112 0.945679 -0.320152 0.0565186 0.945679 -0.194548 0.0474958 0.979743 -0.306159 0.109352 0.945679 -0.30984 0.0984407 0.945679 -0.196 0.0410938 0.979743 -0.198199 0.0286663 0.979743 -0.198976 0.0226517 0.979743 -0.199557 0.0167756 0.979743 -0.323016 0.0367726 0.945679 -0.32396 0.0272333 0.945679 -0.200187 0.0054483 0.979743 -0.199957 0.0110405 0.979743 -0.68681 1.55016e-16 0.726837 -0.732042 -1.77628e-16 0.68126 -0.677048 -0.0184265 0.735709 -0.324608 -0.017923 0.945679 -0.60592 -0.0164907 0.795355 -0.637378 -1.67703e-16 0.770551 -0.52204 -0.0594299 0.850848 -0.429871 -0.0489372 0.901563 -0.523565 -0.044013 0.850848 -0.520001 -0.0752096 0.850848 -0.428192 -0.0619308 0.901563 -0.517411 -0.0913421 0.850848 -0.42344 -0.0887794 0.901563 -0.426059 -0.0752151 0.901563 -0.593246 -0.124381 0.795355 -0.510421 -0.124611 0.850848 -0.514231 -0.107815 0.850848 -0.313054 -0.0876856 0.945679 -0.494797 -0.176729 0.850848 -0.407438 -0.145526 0.901563 -0.500746 -0.159094 0.850848 -0.292055 -0.142813 0.945679 -0.388667 -0.190056 0.901563 -0.303397 -0.308438 0.901563 -0.368449 -0.37457 0.850848 -0.28876 -0.322182 0.901563 -0.22798 -0.231768 0.945679 -0.27322 -0.335462 0.901563 -0.239486 -0.360319 0.901563 -0.290835 -0.437576 0.850848 -0.221342 -0.371741 0.901563 -0.179956 -0.270753 0.945679 -0.202391 -0.382389 0.901563 -0.182681 -0.392187 0.901563 -0.162266 -0.401065 0.901563 -0.141208 -0.408954 0.901563 -0.0974562 -0.421528 0.901563 -0.118352 -0.511908 0.850848 -0.0732311 -0.316747 0.945679 -0.0290041 -0.431674 0.901563 -0.0058071 -0.432608 0.901563 0.017415 -0.432296 0.901563 0.0405619 -0.430741 0.901563 0.0635345 -0.427956 0.901563 0.0862361 -0.423965 0.901563 0.13046 -0.412509 0.901563 0.158433 -0.500956 0.850848 0.151813 -0.405137 0.901563 0.0980313 -0.30997 0.945679 0.172558 -0.396746 0.901563 0.192628 -0.387399 0.901563 0.159276 -0.283413 0.945679 0.248245 -0.354342 0.901563 0.199214 -0.256915 0.945679 0.310375 -0.301415 0.901563 0.376923 -0.366042 0.850848 0.323651 -0.287113 0.901563 0.233224 -0.226491 0.945679 0.252497 -0.204785 0.945679 0.35811 -0.242776 0.901563 0.434894 -0.294831 0.850848 0.367861 -0.227731 0.901563 0.269093 -0.182429 0.945679 0.276421 -0.171123 0.945679 0.376782 -0.212647 0.901563 0.289224 -0.148462 0.945679 0.294743 -0.137179 0.945679 0.409967 -0.138241 0.901563 0.404745 -0.152857 0.901563 0.491527 -0.185632 0.850848 0.304136 -0.114861 0.945679 0.30806 -0.103878 0.945679 0.311504 -0.0930424 0.945679 0.314494 -0.0823722 0.945679 0.317056 -0.0718834 0.945679 0.319215 -0.0615891 0.945679 0.320997 -0.0515007 0.945679 0.323526 -0.0319746 0.945679 0.324319 -0.0225494 0.945679 0.324828 -0.0133547 0.945679 0.325073 -0.00439309 0.945679 0.325073 0.00439303 0.945679 0.324828 0.0133548 0.945679 0.324319 0.0225494 0.945679 0.323526 0.0319746 0.945679 0.322426 0.0416268 0.945679 0.320997 0.0515007 0.945679 0.319215 0.0615891 0.945679 0.418529 0.109621 0.901563 0.508267 0.133125 0.850848 0.41455 0.123821 0.901563 0.314494 0.0823722 0.945679 0.311504 0.0930424 0.945679 0.30806 0.103878 0.945679 0.392245 0.182558 0.901563 0.289224 0.148462 0.945679 0.376782 0.212647 0.901563 0.276421 0.171123 0.945679 0.35811 0.242776 0.901563 0.261124 0.193664 0.945679 0.336023 0.272529 0.901563 0.32365 0.287113 0.901563 0.233224 0.226491 0.945679 0.296192 0.315363 0.901563 0.281102 0.328884 0.901563 0.248245 0.354342 0.901563 0.301471 0.430317 0.850848 0.186538 0.266261 0.945679 0.211964 0.377166 0.901563 0.192628 0.387399 0.901563 0.172558 0.396746 0.901563 0.151813 0.405137 0.901563 0.108574 0.418802 0.901563 0.131853 0.508598 0.850848 0.0862361 0.423965 0.901563 0.104726 0.514869 0.850848 0.0648001 0.318579 0.945679 0.040562 0.430741 0.901563 0.0174149 0.432296 0.901563 -0.00580703 0.432608 0.901563 -0.0290039 0.431674 0.901563 -0.0520761 0.429502 0.901563 -0.0749252 0.42611 0.901563 -0.119579 0.415794 0.901563 -0.145218 0.504945 0.850848 -0.0898547 0.312438 0.945679 -0.162266 0.401065 0.901563 -0.182682 0.392187 0.901563 -0.221342 0.371741 0.901563 -0.2688 0.451447 0.850848 -0.239486 0.360319 0.901563 -0.166322 0.279336 0.945679 -0.27322 0.335461 0.901563 -0.331801 0.407388 0.850848 -0.205305 0.252074 0.945679 -0.247932 0.210288 0.945679 -0.256893 0.199242 0.945679 -0.26519 0.188058 0.945679 -0.272836 0.176782 0.945679 -0.286248 0.154122 0.945679 -0.292055 0.142813 0.945679 -0.412336 0.131005 0.901563 -0.313054 0.0876857 0.945679 -0.372424 0.22019 0.901563 -0.315827 0.0771042 0.945679 -0.407438 0.145527 0.901563 -0.321754 0.0465365 0.945679 -0.426059 0.0752152 0.901563 -0.429871 0.0489371 0.901563 -0.431126 0.0362422 0.901563 -0.324608 0.017923 0.945679 -0.324982 0.00884472 0.945679 -0.431989 -0.023852 0.901563 -0.431126 -0.0362422 0.901563 -0.420303 -0.102611 0.901563 -0.50594 -0.141712 0.850848 -0.58885 -0.143759 0.795355 -0.488051 -0.194585 0.850848 -0.570826 -0.203885 0.795355 -0.563043 -0.224484 0.795355 -0.480467 -0.212625 0.850848 -0.554293 -0.245296 0.795355 -0.38094 -0.205106 0.901563 -0.462618 -0.249083 0.850848 -0.452276 -0.267402 0.850848 -0.400694 -0.339855 0.850848 -0.317126 -0.294303 0.901563 -0.350674 -0.391261 0.850848 -0.311847 -0.422858 0.850848 -0.359764 -0.487833 0.795355 -0.256789 -0.3482 0.901563 -0.2688 -0.451447 0.850848 -0.245787 -0.464377 0.850848 -0.221851 -0.476277 0.850848 -0.171485 -0.496639 0.850848 -0.197835 -0.572951 0.795355 -0.145218 -0.504945 0.850848 -0.167532 -0.582533 0.795355 -0.119579 -0.415794 0.901563 -0.0909899 -0.517473 0.850848 -0.0632419 -0.521592 0.850848 -0.0352229 -0.52423 0.850848 -0.00705222 -0.525364 0.850848 0.021149 -0.524986 0.850848 0.0492588 -0.523098 0.850848 0.0771571 -0.519716 0.850848 0.131854 -0.508598 0.850848 0.152114 -0.586747 0.795355 0.108574 -0.418802 0.901563 0.184364 -0.492004 0.850848 0.209557 -0.481813 0.850848 0.257412 -0.458035 0.850848 0.296965 -0.528415 0.795355 0.279943 -0.444623 0.850848 0.211965 -0.377166 0.901563 0.301471 -0.430317 0.850848 0.265114 -0.341903 0.901563 0.341374 -0.399401 0.850848 0.296192 -0.315363 0.901563 0.408071 -0.330962 0.850848 0.470773 -0.381816 0.795355 0.422014 -0.312989 0.850848 0.336023 -0.272529 0.901563 0.347505 -0.257729 0.901563 0.457569 -0.258241 0.850848 0.3849 -0.197574 0.901563 0.392245 -0.182558 0.901563 0.398849 -0.16764 0.901563 0.41455 -0.123821 0.901563 0.418529 -0.109621 0.901563 0.421938 -0.0956626 0.901563 0.424812 -0.081963 0.901563 0.427184 -0.0685373 0.901563 0.429086 -0.0553972 0.901563 0.430549 -0.0425519 0.901563 0.431605 -0.0300088 0.901563 0.432282 -0.0177725 0.901563 0.432608 -0.00584634 0.901563 0.432608 0.00584626 0.901563 0.432282 0.0177726 0.901563 0.431605 0.0300088 0.901563 0.430549 0.0425519 0.901563 0.429086 0.0553971 0.901563 0.427184 0.0685373 0.901563 0.424812 0.081963 0.901563 0.421938 0.0956625 0.901563 0.409967 0.138241 0.901563 0.491527 0.185632 0.850848 0.398849 0.16764 0.901563 0.467427 0.239936 0.850848 0.53925 0.276804 0.795355 0.457569 0.258241 0.850848 0.3849 0.197574 0.901563 0.446735 0.276559 0.850848 0.515379 0.319054 0.795355 0.434894 0.294831 0.850848 0.367861 0.227731 0.901563 0.347505 0.257729 0.901563 0.408071 0.330962 0.850848 0.376923 0.366041 0.850848 0.43484 0.422286 0.795355 0.359699 0.38298 0.850848 0.310375 0.301415 0.901563 0.341374 0.399401 0.850848 0.265114 0.341903 0.901563 0.279943 0.444623 0.850848 0.257412 0.458035 0.850848 0.23393 0.470462 0.850848 0.209557 0.481813 0.850848 0.158433 0.500956 0.850848 0.182777 0.57793 0.795355 0.13046 0.412509 0.901563 0.0771571 0.519716 0.850848 0.0492589 0.523098 0.850848 0.0211489 0.524986 0.850848 -0.00705213 0.525364 0.850848 -0.0352227 0.52423 0.850848 -0.0632418 0.521592 0.850848 -0.118352 0.511908 0.850848 -0.136537 0.590566 0.795355 -0.0974562 0.421528 0.901563 -0.171485 0.496639 0.850848 -0.197058 0.487058 0.850848 -0.221851 0.476277 0.850848 -0.202391 0.382389 0.901563 -0.290835 0.437576 0.850848 -0.256789 0.3482 0.901563 -0.350674 0.391261 0.850848 -0.329949 0.279852 0.901563 -0.341874 0.265151 0.901563 -0.352916 0.250268 0.901563 -0.363091 0.235262 0.901563 -0.38094 0.205106 0.901563 -0.395637 0.175085 0.901563 -0.401883 0.16023 0.901563 -0.452276 0.267402 0.850848 -0.577688 0.18354 0.795355 -0.500746 0.159094 0.850848 -0.570826 0.203885 0.795355 -0.416613 0.116692 0.901563 -0.420303 0.10261 0.901563 -0.494797 0.176729 0.850848 -0.42344 0.0887794 0.901563 -0.428192 0.0619309 0.901563 -0.517411 0.0913422 0.850848 -0.52204 0.0594298 0.850848 -0.523565 0.044013 0.850848 -0.432487 0.0117706 0.901563 -0.431989 0.023852 0.901563 -0.58279 -4.20884e-16 0.812623 -0.524613 -0.0289662 0.850848 -0.797813 -0.0217132 0.602514 -0.740552 -0.0201548 0.671697 -0.773792 -1.35159e-16 0.63344 -0.672952 -0.0766099 0.735709 -0.738222 -0.062058 0.671697 -0.736072 -0.0837956 0.671697 -0.670323 -0.0969512 0.735709 -0.599902 -0.0867659 0.795355 -0.645502 -0.205085 0.735708 -0.577689 -0.18354 0.795355 -0.652197 -0.182679 0.735708 -0.472002 -0.230806 0.850848 -0.533701 -0.287356 0.795355 -0.544528 -0.266271 0.795355 -0.608449 -0.297528 0.735708 -0.478971 -0.371481 0.795355 -0.444298 -0.412323 0.795355 -0.496453 -0.460725 0.735709 -0.425063 -0.432125 0.795355 -0.385122 -0.357406 0.850848 -0.404557 -0.451381 0.795355 -0.331801 -0.407388 0.850848 -0.335524 -0.504812 0.795355 -0.310103 -0.520814 0.795355 -0.283553 -0.535732 0.795355 -0.227337 -0.561898 0.795355 -0.254024 -0.627858 0.735708 -0.197058 -0.487058 0.850848 -0.136537 -0.590566 0.795355 -0.104971 -0.596986 0.795355 -0.0729594 -0.601737 0.795355 -0.0406351 -0.604781 0.795355 -0.00813583 -0.60609 0.795355 0.0243987 -0.605653 0.795355 0.0568277 -0.603474 0.795355 0.120818 -0.593981 0.795355 0.135001 -0.663708 0.735709 0.104726 -0.514869 0.850848 0.182777 -0.57793 0.795355 0.212692 -0.567603 0.795355 0.241756 -0.555846 0.795355 0.23393 -0.470462 0.850848 0.322958 -0.512942 0.795355 0.371429 -0.479011 0.795355 0.41503 -0.535241 0.735708 0.393828 -0.460772 0.795355 0.321958 -0.415211 0.850848 0.359699 -0.382981 0.850848 0.43484 -0.422286 0.795355 0.393045 -0.348673 0.850848 0.501717 -0.340133 0.795355 0.446735 -0.276559 0.850848 0.54954 -0.255766 0.795355 0.53925 -0.276804 0.795355 0.602551 -0.309297 0.735709 0.467427 -0.239936 0.850848 0.476347 -0.221701 0.850848 0.484367 -0.203584 0.850848 0.567052 -0.214155 0.795355 0.497869 -0.167882 0.850848 0.503435 -0.15037 0.850848 0.508267 -0.133125 0.850848 0.512407 -0.116174 0.850848 0.515897 -0.0995369 0.850848 0.518777 -0.0832325 0.850848 0.521087 -0.067275 0.850848 0.522864 -0.0516756 0.850848 0.524146 -0.036443 0.850848 0.524968 -0.0215831 0.850848 0.525364 -0.00709986 0.850848 0.525364 0.00709976 0.850848 0.524968 0.0215832 0.850848 0.524146 0.036443 0.850848 0.522864 0.0516756 0.850848 0.521087 0.0672749 0.850848 0.518777 0.0832325 0.850848 0.515897 0.0995369 0.850848 0.512407 0.116174 0.850848 0.586365 0.153581 0.795355 0.503435 0.15037 0.850848 0.497869 0.167882 0.850848 0.567052 0.214155 0.795355 0.484367 0.203584 0.850848 0.476347 0.221701 0.850848 0.486859 0.361081 0.795355 0.54401 0.403468 0.735708 0.470773 0.381816 0.795355 0.422014 0.312989 0.850848 0.393045 0.348673 0.850848 0.414969 0.441828 0.795355 0.371429 0.479011 0.795355 0.41503 0.535241 0.735709 0.347794 0.496437 0.795355 0.321958 0.415211 0.850848 0.322958 0.512942 0.795355 0.296965 0.528415 0.795355 0.269875 0.542751 0.795355 0.212693 0.567603 0.795355 0.23766 0.634232 0.735709 0.184364 0.492003 0.850848 0.152114 0.586747 0.795355 0.120818 0.593981 0.795355 0.0890127 0.599573 0.795355 0.0568279 0.603475 0.795355 0.0243986 0.605653 0.795355 -0.00813573 0.60609 0.795355 -0.0406349 0.604781 0.795355 -0.104971 0.596986 0.795355 -0.117294 0.667065 0.735708 -0.09099 0.517473 0.850848 -0.167532 0.582532 0.795355 -0.197835 0.572951 0.795355 -0.227337 0.561897 0.795355 -0.283553 0.535732 0.795355 -0.316839 0.59862 0.735709 -0.310103 0.520814 0.795355 -0.245787 0.464377 0.850848 -0.335523 0.504812 0.795355 -0.311847 0.422858 0.850848 -0.382785 0.469986 0.795355 -0.425063 0.432125 0.795355 -0.474961 0.482851 0.735708 -0.415176 0.322003 0.850848 -0.428585 0.303928 0.850848 -0.404557 0.451381 0.795355 -0.440942 0.285705 0.850848 -0.521771 0.30849 0.795355 -0.480467 0.212625 0.850848 -0.488051 0.194585 0.850848 -0.50594 0.141713 0.850848 -0.510421 0.124611 0.850848 -0.514231 0.107815 0.850848 -0.520001 0.0752097 0.850848 -0.604014 0.0507758 0.795355 -0.524613 0.0289662 0.850848 -0.602254 0.0685615 0.795355 -0.525217 0.0142943 0.850848 -0.8496 -0.0231227 0.52692 -0.812562 0 0.582874 -0.848651 -3.36275e-16 0.528953 -0.605222 -0.033417 0.795355 -0.604014 -0.0507759 0.795355 -0.602254 -0.0685616 0.795355 -0.596914 -0.105377 0.795355 -0.729545 -0.128792 0.671697 -0.662885 -0.138982 0.735708 -0.666985 -0.117747 0.735708 -0.657974 -0.160634 0.735708 -0.725061 -0.152018 0.671697 -0.58368 -0.163487 0.795355 -0.637834 -0.227818 0.735708 -0.629138 -0.250836 0.735708 -0.69766 -0.249186 0.671697 -0.688148 -0.274363 0.671697 -0.596352 -0.321088 0.735709 -0.535196 -0.415088 0.735709 -0.462263 -0.392076 0.795355 -0.474961 -0.482851 0.735709 -0.401996 -0.545098 0.735709 -0.427719 -0.525157 0.735709 -0.467837 -0.574414 0.671697 -0.382785 -0.469986 0.795355 -0.37491 -0.56407 0.735708 -0.346505 -0.581951 0.735708 -0.285983 -0.61396 0.735708 -0.312807 -0.671546 0.671697 -0.255939 -0.54946 0.795355 -0.221058 -0.640208 0.735708 -0.187198 -0.650915 0.735708 -0.152565 -0.659892 0.735708 -0.117293 -0.667065 0.735708 -0.0815239 -0.672374 0.735709 -0.0454052 -0.675775 0.735709 -0.00909088 -0.677237 0.735709 0.0634986 -0.674315 0.735709 0.0694545 -0.737563 0.671697 0.0994617 -0.669955 0.735709 0.108791 -0.732794 0.671697 0.0890127 -0.599573 0.795355 0.16997 -0.655624 0.735709 0.204232 -0.645772 0.735709 0.23766 -0.634232 0.735709 0.301555 -0.606463 0.735708 0.329839 -0.663347 0.671697 0.331825 -0.590445 0.735708 0.269875 -0.542751 0.795355 0.360869 -0.573155 0.735708 0.347794 -0.496437 0.795355 0.440059 -0.514861 0.735708 0.414969 -0.441828 0.795355 0.485885 -0.471857 0.735708 0.453439 -0.402249 0.795355 0.526036 -0.426637 0.735709 0.486858 -0.361081 0.795355 0.560613 -0.38006 0.735709 0.515379 -0.319054 0.795355 0.527877 -0.297921 0.795355 0.558792 -0.234866 0.795355 0.648968 -0.193839 0.735709 0.641793 -0.216413 0.735709 0.70199 -0.236712 0.671697 0.574369 -0.193678 0.795355 0.58079 -0.173475 0.795355 0.586365 -0.153581 0.795355 0.591142 -0.134025 0.795355 0.595168 -0.114831 0.795355 0.59849 -0.0960216 0.795355 0.601155 -0.0776122 0.795355 0.603206 -0.0596159 0.795355 0.604685 -0.0420427 0.795355 0.605633 -0.0248995 0.795355 0.606089 -0.00819079 0.795355 0.606089 0.00819068 0.795355 0.605633 0.0248996 0.795355 0.604684 0.0420427 0.795355 0.603205 0.0596159 0.795355 0.595168 0.114831 0.795355 0.591142 0.134024 0.795355 0.641793 0.216413 0.735709 0.648968 0.193839 0.735709 0.709838 0.21202 0.671697 0.58079 0.173475 0.795355 0.574369 0.193678 0.795355 0.61405 0.28579 0.735708 0.624388 0.262437 0.735708 0.682953 0.287052 0.671697 0.558792 0.234866 0.795355 0.54954 0.255766 0.795355 0.602551 0.309297 0.735708 0.527877 0.297921 0.795355 0.575878 0.356507 0.735708 0.501718 0.340133 0.795355 0.526036 0.426637 0.735708 0.453438 0.402249 0.795355 0.485884 0.471857 0.735709 0.463681 0.493693 0.735709 0.393828 0.460772 0.795355 0.388621 0.554713 0.735709 0.360869 0.573155 0.735709 0.331825 0.590445 0.735709 0.270136 0.621096 0.735709 0.295473 0.679352 0.671697 0.241756 0.555846 0.795355 0.204232 0.645772 0.735709 0.16997 0.655624 0.735708 0.135001 0.663708 0.735708 0.0994617 0.669956 0.735708 0.0634988 0.674315 0.735708 0.0272627 0.676749 0.735708 -0.00909077 0.677237 0.735708 -0.0815238 0.672374 0.735708 -0.0891704 0.73544 0.671697 -0.0729593 0.601737 0.795355 -0.152565 0.659891 0.735709 -0.187198 0.650915 0.735709 -0.221058 0.640208 0.735709 -0.254024 0.627857 0.735709 -0.255939 0.54946 0.795355 -0.346505 0.581951 0.735709 -0.427719 0.525157 0.735709 -0.401996 0.545098 0.735709 -0.439702 0.596226 0.671697 -0.359764 0.487833 0.795355 -0.49444 0.350629 0.795355 -0.452047 0.504368 0.735709 -0.508696 0.329605 0.795355 -0.544528 0.266271 0.795355 -0.554293 0.245296 0.795355 -0.563043 0.224484 0.795355 -0.58885 0.143759 0.795355 -0.58368 0.163488 0.795355 -0.652197 0.182679 0.735709 -0.645502 0.205085 0.735709 -0.637834 0.227818 0.735709 -0.596914 0.105377 0.795355 -0.593246 0.124381 0.795355 -0.599902 0.0867661 0.795355 -0.666985 0.117747 0.735709 -0.672952 0.0766098 0.735709 -0.674918 0.0567363 0.735709 -0.605222 0.033417 0.795355 -0.60592 0.0164907 0.795355 -0.676268 -0.0373398 0.735709 -0.674918 -0.0567363 0.735709 -0.792986 -0.0902749 0.602514 -0.846928 -0.0711962 0.52692 -0.844461 -0.0961348 0.52692 -0.713371 -0.199813 0.671697 -0.719689 -0.175701 0.671697 -0.775337 -0.189287 0.602514 -0.760641 -0.241666 0.602514 -0.706047 -0.224321 0.671697 -0.76853 -0.215263 0.602514 -0.619361 -0.27409 0.735708 -0.677454 -0.299799 0.671697 -0.741357 -0.295577 0.602514 -0.729836 -0.32298 0.602514 -0.621725 -0.402841 0.671697 -0.552481 -0.391788 0.735709 -0.516527 -0.438101 0.735709 -0.543018 -0.503939 0.671697 -0.51951 -0.528141 0.671697 -0.452047 -0.504368 0.735709 -0.439702 -0.596226 0.671697 -0.410075 -0.616978 0.671697 -0.373353 -0.705396 0.602514 -0.346557 -0.654768 0.671697 -0.316839 -0.59862 0.735708 -0.27785 -0.686748 0.671697 -0.241792 -0.700257 0.671697 -0.204756 -0.711968 0.671697 -0.166875 -0.721786 0.671697 -0.128295 -0.729632 0.671697 -0.0891705 -0.73544 0.671697 -0.049664 -0.739159 0.671697 0.0321257 -0.797461 0.602514 0.02982 -0.740225 0.671697 0.0272628 -0.676749 0.735709 0.147663 -0.72596 0.671697 0.185912 -0.717119 0.671697 0.223389 -0.706343 0.671697 0.31832 -0.731881 0.602514 0.295473 -0.679352 0.671697 0.270136 -0.621095 0.735709 0.362949 -0.645826 0.671697 0.453958 -0.585444 0.671697 0.425072 -0.606743 0.671697 0.45794 -0.653657 0.602514 0.388621 -0.554713 0.735708 0.531458 -0.516115 0.671697 0.507172 -0.539999 0.671697 0.546388 -0.581753 0.602514 0.463681 -0.493693 0.735708 0.506667 -0.449468 0.735708 0.575376 -0.466653 0.671697 0.54401 -0.403468 0.735709 0.645168 -0.364117 0.671697 0.629893 -0.389946 0.671697 0.678598 -0.420097 0.602514 0.575878 -0.356507 0.735709 0.589843 -0.332893 0.735709 0.659068 -0.338308 0.671697 0.61405 -0.28579 0.735709 0.624388 -0.262437 0.735709 0.633618 -0.239294 0.735709 0.655197 -0.171609 0.735709 0.660534 -0.149757 0.735708 0.665033 -0.128311 0.735708 0.668746 -0.107293 0.735708 0.671723 -0.0867229 0.735708 0.674015 -0.066614 0.735708 0.675667 -0.046978 0.735708 0.676727 -0.0278224 0.735708 0.677236 -0.0091523 0.735708 0.677236 0.00915217 0.735708 0.676727 0.0278226 0.735709 0.675667 0.046978 0.735709 0.674014 0.066614 0.735709 0.72741 0.140346 0.671697 0.731471 0.117357 0.671697 0.78803 0.126431 0.602514 0.668746 0.107293 0.735709 0.665033 0.128311 0.735709 0.660534 0.149757 0.735709 0.655197 0.171609 0.735709 0.633618 0.239294 0.735709 0.659068 0.338308 0.671697 0.589843 0.332893 0.735708 0.629893 0.389946 0.671697 0.560613 0.38006 0.735708 0.595036 0.441311 0.671697 0.531458 0.516115 0.671697 0.55419 0.491627 0.671697 0.597041 0.52964 0.602514 0.506667 0.449468 0.735708 0.453958 0.585444 0.671697 0.481334 0.563152 0.671697 0.518552 0.606696 0.602514 0.440059 0.514861 0.735709 0.425072 0.606743 0.671697 0.394717 0.626914 0.671697 0.329839 0.663347 0.671697 0.355343 0.714638 0.602514 0.301555 0.606463 0.735709 0.259952 0.693721 0.671697 0.223388 0.706343 0.671697 0.185912 0.717119 0.671697 0.147663 0.725961 0.671697 0.108791 0.732794 0.671697 0.0694547 0.737563 0.671697 -0.0107123 0.798036 0.602514 -0.0496637 0.739159 0.671697 -0.00994344 0.740759 0.671697 -0.0535038 0.796313 0.602514 -0.045405 0.675775 0.735708 -0.128295 0.729632 0.671697 -0.166875 0.721786 0.671697 -0.204756 0.711968 0.671697 -0.241792 0.700257 0.671697 -0.346557 0.654768 0.671697 -0.312807 0.671546 0.671697 -0.336994 0.723472 0.602514 -0.285983 0.61396 0.735709 -0.379005 0.636536 0.671697 -0.37491 0.56407 0.735709 -0.467837 0.574414 0.671697 -0.51951 0.528141 0.671697 -0.608661 0.516245 0.602514 -0.552481 0.391788 0.735708 -0.494447 0.551675 0.671697 -0.568411 0.368297 0.735708 -0.706047 0.224322 0.671697 -0.69766 0.249187 0.671697 -0.751604 0.268454 0.602514 -0.608449 0.297528 0.735708 -0.61936 0.27409 0.735709 -0.629138 0.250836 0.735709 -0.657974 0.160634 0.735709 -0.729545 0.128792 0.671697 -0.733197 0.106045 0.671697 -0.670323 0.0969513 0.735709 -0.662885 0.138982 0.735709 -0.736072 0.0837955 0.671697 -0.738222 0.0620579 0.671697 -0.677048 0.0184265 0.735708 -0.676268 0.0373398 0.735709 -0.936345 -0.0254835 0.350155 -0.940465 -8.88808e-16 0.339891 -0.964182 1.83511e-16 0.265241 -0.739699 -0.0408421 0.671697 -0.912879 -5.23527e-16 0.40823 -0.896009 -0.0243857 0.443367 -0.733197 -0.106045 0.671697 -0.841163 -0.12166 0.52692 -0.789889 -0.114244 0.602514 -0.836973 -0.147757 0.52692 -0.781124 -0.163772 0.602514 -0.785955 -0.13875 0.602514 -0.800393 -0.28588 0.52692 -0.751604 -0.268454 0.602514 -0.810015 -0.257354 0.52692 -0.665519 -0.325435 0.671697 -0.716978 -0.350599 0.602514 -0.64817 -0.549756 0.52692 -0.585006 -0.542904 0.602514 -0.60866 -0.516245 0.602514 -0.564975 -0.479193 0.671697 -0.567256 -0.632911 0.52692 -0.504011 -0.618829 0.602514 -0.532678 -0.594332 0.602514 -0.494447 -0.551675 0.671697 -0.4737 -0.642328 0.602514 -0.441783 -0.664684 0.602514 -0.379006 -0.636536 0.671697 -0.336994 -0.723472 0.602514 -0.299334 -0.739849 0.602514 -0.260488 -0.754402 0.602514 -0.220588 -0.767019 0.602514 -0.179778 -0.777597 0.602514 -0.138215 -0.786049 0.602514 -0.0569772 -0.848003 0.52692 -0.0107124 -0.798036 0.602514 -0.0535041 -0.796313 0.602514 -0.0114078 -0.849839 0.52692 -0.00994356 -0.740759 0.671697 0.0748249 -0.794593 0.602514 0.117203 -0.789456 0.602514 0.159081 -0.782093 0.602514 0.200288 -0.772568 0.602514 0.240661 -0.760959 0.602514 0.259951 -0.693721 0.671697 0.355343 -0.714638 0.602514 0.391013 -0.695763 0.602514 0.394717 -0.626914 0.671697 0.489059 -0.630712 0.602514 0.481334 -0.563152 0.671697 0.619865 -0.502736 0.602514 0.597041 -0.52964 0.602514 0.635796 -0.56402 0.52692 0.55419 -0.491626 0.671697 0.66061 -0.447852 0.602514 0.641045 -0.475435 0.602514 0.682657 -0.506296 0.52692 0.595036 -0.441311 0.671697 0.613196 -0.415708 0.671697 0.73576 -0.309248 0.602514 0.723578 -0.336767 0.602514 0.770547 -0.358627 0.52692 0.671645 -0.312596 0.671697 0.682952 -0.287052 0.671697 0.693048 -0.261739 0.671697 0.772065 -0.202219 0.602514 0.764725 -0.228414 0.602514 0.814364 -0.243241 0.52692 0.709838 -0.21202 0.671697 0.716652 -0.187705 0.671697 0.72249 -0.163804 0.671697 0.72741 -0.140346 0.671697 0.731471 -0.117357 0.671697 0.734728 -0.0948571 0.671697 0.737234 -0.0728621 0.671697 0.739042 -0.0513844 0.671697 0.740201 -0.030432 0.671697 0.740758 -0.0100107 0.671697 0.740758 0.0100106 0.671697 0.740201 0.0304322 0.671697 0.739042 0.0513844 0.671697 0.737234 0.0728621 0.671697 0.734728 0.094857 0.671697 0.72249 0.163804 0.671697 0.716652 0.187705 0.671697 0.764725 0.228414 0.602514 0.70199 0.236712 0.671697 0.693048 0.261739 0.671697 0.73576 0.309248 0.602514 0.671645 0.312596 0.671697 0.678598 0.420097 0.602514 0.695054 0.392271 0.602514 0.740171 0.417735 0.52692 0.645168 0.364117 0.671697 0.613196 0.415708 0.671697 0.641045 0.475435 0.602514 0.575376 0.466653 0.671697 0.572552 0.556023 0.602514 0.507172 0.539999 0.671697 0.489059 0.630712 0.602514 0.45794 0.653657 0.602514 0.416394 0.740926 0.52692 0.391013 0.695763 0.602514 0.362949 0.645826 0.671697 0.31832 0.731881 0.602514 0.280052 0.747361 0.602514 0.240661 0.760959 0.602514 0.200287 0.772568 0.602514 0.159081 0.782093 0.602514 0.117203 0.789456 0.602514 0.0342109 0.849226 0.52692 0.0321255 0.797461 0.602514 0.0298198 0.740226 0.671697 -0.0960653 0.792306 0.602514 -0.138215 0.786049 0.602514 -0.179778 0.777597 0.602514 -0.220588 0.767019 0.602514 -0.318765 0.787874 0.52692 -0.299334 0.739848 0.602514 -0.27785 0.686748 0.671697 -0.373354 0.705396 0.602514 -0.408311 0.685754 0.602514 -0.410075 0.616978 0.671697 -0.4737 0.642328 0.602514 -0.504011 0.618829 0.602514 -0.559679 0.568978 0.602514 -0.543018 0.503939 0.671697 -0.532678 0.594332 0.602514 -0.621725 0.402841 0.671697 -0.652287 0.351205 0.671697 -0.665519 0.325435 0.671697 -0.677454 0.299799 0.671697 -0.688148 0.274363 0.671697 -0.713371 0.199814 0.671697 -0.719689 0.175701 0.671697 -0.76064 0.241667 0.602514 -0.725061 0.152018 0.671697 -0.785955 0.13875 0.602514 -0.792986 0.0902748 0.602514 -0.795303 0.0668564 0.602514 -0.740552 0.0201549 0.671697 -0.739699 0.0408421 0.671697 -0.796894 -0.0440001 0.602514 -0.795303 -0.0668564 0.602514 -0.825666 -0.201574 0.52692 -0.831829 -0.174403 0.52692 -0.877266 -0.18393 0.443366 -0.818417 -0.229236 0.52692 -0.870766 -0.212584 0.443366 -0.789481 -0.314764 0.52692 -0.777211 -0.343945 0.52692 -0.832605 -0.331957 0.443366 -0.819665 -0.362733 0.443366 -0.693287 -0.491639 0.52692 -0.630659 -0.489128 0.602514 -0.622979 -0.578146 0.52692 -0.55968 -0.568978 0.602514 -0.536728 -0.658999 0.52692 -0.504449 -0.684022 0.52692 -0.458567 -0.770158 0.443366 -0.397589 -0.751185 0.52692 -0.434815 -0.730268 0.52692 -0.408311 -0.685754 0.602514 -0.358869 -0.770434 0.52692 -0.318764 -0.787874 0.52692 -0.277397 -0.803372 0.52692 -0.234907 -0.816807 0.52692 -0.155227 -0.882797 0.443366 -0.102301 -0.843736 0.52692 -0.147187 -0.837073 0.52692 -0.107889 -0.889824 0.443366 -0.0960654 -0.792306 0.602514 0.0342111 -0.849226 0.52692 0.079682 -0.846172 0.52692 0.124811 -0.840701 0.52692 0.169407 -0.832861 0.52692 0.213289 -0.822717 0.52692 0.31452 -0.839347 0.443367 0.338983 -0.779388 0.52692 0.29823 -0.795873 0.52692 0.280051 -0.747361 0.602514 0.378409 -0.761027 0.52692 0.416395 -0.740926 0.52692 0.425237 -0.675389 0.602514 0.487665 -0.696088 0.52692 0.520805 -0.671653 0.52692 0.518552 -0.606696 0.602514 0.581855 -0.619516 0.52692 0.572552 -0.556023 0.602514 0.722647 -0.447367 0.52692 0.695054 -0.392271 0.602514 0.710029 -0.364466 0.602514 0.746636 -0.281977 0.602514 0.75627 -0.255015 0.602514 0.778354 -0.17647 0.602514 0.783655 -0.151198 0.602514 0.78803 -0.126431 0.602514 0.791539 -0.102192 0.602514 0.794239 -0.078496 0.602514 0.796186 -0.0553575 0.602514 0.797435 -0.0327851 0.602514 0.798035 -0.0107848 0.602514 0.798035 0.0107846 0.602514 0.797435 0.0327853 0.602514 0.796186 0.0553575 0.602514 0.794239 0.078496 0.602514 0.791539 0.102192 0.602514 0.828879 0.187925 0.52692 0.834524 0.161013 0.52692 0.880109 0.169808 0.443367 0.783655 0.151198 0.602514 0.778354 0.17647 0.602514 0.772065 0.202219 0.602514 0.795102 0.300281 0.52692 0.805361 0.271569 0.52692 0.849352 0.286403 0.443367 0.75627 0.255015 0.602514 0.746636 0.281977 0.602514 0.812637 0.378216 0.443366 0.756118 0.388125 0.52692 0.770547 0.358627 0.52692 0.723578 0.336766 0.602514 0.710029 0.364467 0.602514 0.741919 0.502974 0.443366 0.682657 0.506296 0.52692 0.703491 0.476923 0.52692 0.66061 0.447852 0.602514 0.619866 0.502736 0.602514 0.635796 0.56402 0.52692 0.613638 0.653356 0.443366 0.552212 0.646078 0.52692 0.581855 0.619516 0.52692 0.546388 0.581753 0.602514 0.520805 0.671653 0.52692 0.487665 0.696088 0.52692 0.425238 0.675389 0.602514 0.378409 0.761027 0.52692 0.338983 0.779388 0.52692 0.29823 0.795873 0.52692 0.256283 0.810355 0.52692 0.213288 0.822717 0.52692 0.131628 0.886623 0.443366 0.0796821 0.846172 0.52692 0.124811 0.840701 0.52692 0.0840346 0.892393 0.443366 0.074825 0.794593 0.602514 -0.0114076 0.849839 0.52692 -0.0569769 0.848003 0.52692 -0.102301 0.843736 0.52692 -0.147187 0.837073 0.52692 -0.191448 0.828072 0.52692 -0.292549 0.847255 0.443366 -0.277397 0.803372 0.52692 -0.260488 0.754402 0.602514 -0.358869 0.770434 0.52692 -0.397589 0.751185 0.52692 -0.496158 0.746494 0.443367 -0.504449 0.684022 0.52692 -0.47046 0.70783 0.52692 -0.441783 0.664684 0.602514 -0.598241 0.667483 0.443367 -0.596009 0.605911 0.52692 -0.567256 0.632911 0.52692 -0.585006 0.542904 0.602514 -0.64817 0.549756 0.52692 -0.771573 0.456182 0.443366 -0.702723 0.378361 0.602514 -0.716978 0.350598 0.602514 -0.729836 0.32298 0.602514 -0.741357 0.295577 0.602514 -0.73161 0.432554 0.52692 -0.781124 0.163772 0.602514 -0.775337 0.189287 0.602514 -0.825666 0.201574 0.52692 -0.76853 0.215264 0.602514 -0.810015 0.257354 0.52692 -0.800393 0.28588 0.52692 -0.789889 0.114245 0.602514 -0.836973 0.147757 0.52692 -0.844461 0.0961347 0.52692 -0.846928 0.0711962 0.52692 -0.797813 0.0217133 0.602514 -0.796894 0.0440001 0.602514 -0.882137 -1.72353e-16 0.470993 -0.848623 -0.0468562 0.52692 -0.991288 -0.0269788 0.128917 -0.96899 -0.026372 0.245688 -0.982976 -5.50413e-16 0.183733 -0.930681 -0.10595 0.350155 -0.965942 -0.081201 0.245689 -0.963128 -0.109644 0.245689 -0.959366 -0.138756 0.245689 -0.927046 -0.134082 0.350155 -0.892718 -0.28363 0.350155 -0.854261 -0.271411 0.443366 -0.901978 -0.252642 0.350155 -0.844113 -0.301496 0.443366 -0.882113 -0.315069 0.350154 -0.771573 -0.456181 0.443366 -0.713276 -0.462161 0.52692 -0.731156 -0.518495 0.443366 -0.671597 -0.520878 0.52692 -0.683575 -0.579786 0.443367 -0.657009 -0.609726 0.443367 -0.596009 -0.605911 0.52692 -0.598241 -0.667483 0.443367 -0.566046 -0.694995 0.443367 -0.518494 -0.7801 0.350155 -0.496158 -0.746494 0.443367 -0.47046 -0.70783 0.52692 -0.419306 -0.792217 0.443366 -0.378472 -0.812518 0.443366 -0.336176 -0.83091 0.443366 -0.29255 -0.847255 0.443366 -0.210995 -0.912619 0.350154 -0.201906 -0.873304 0.443366 -0.191448 -0.828072 0.52692 -0.0600895 -0.894324 0.443366 -0.0120309 -0.89626 0.443366 0.0360798 -0.895614 0.443366 0.0840345 -0.892393 0.443366 0.131628 -0.886623 0.443367 0.17866 -0.878354 0.443367 0.28245 -0.893092 0.350155 0.270282 -0.854619 0.443367 0.256283 -0.810355 0.52692 0.357499 -0.821961 0.443367 0.399079 -0.802597 0.443367 0.499076 -0.792663 0.350155 0.514303 -0.734111 0.443366 0.477576 -0.758516 0.443366 0.45284 -0.71923 0.52692 0.608594 -0.712043 0.350154 0.613638 -0.653356 0.443366 0.582376 -0.681369 0.443366 0.552212 -0.646078 0.52692 0.609718 -0.592115 0.52692 0.670526 -0.594829 0.443366 0.660102 -0.53537 0.52692 0.719946 -0.533952 0.443366 0.703491 -0.476923 0.52692 0.76212 -0.471804 0.443366 0.740171 -0.417735 0.52692 0.756118 -0.388125 0.52692 0.812637 -0.378216 0.443367 0.78352 -0.329322 0.52692 0.795102 -0.300281 0.52692 0.805361 -0.271569 0.52692 0.874155 -0.19819 0.443367 0.867092 -0.227109 0.443367 0.906126 -0.237333 0.350155 0.822181 -0.215346 0.52692 0.828879 -0.187925 0.52692 0.834524 -0.161013 0.52692 0.839183 -0.134638 0.52692 0.842919 -0.108825 0.52692 0.845794 -0.0835913 0.52692 0.847868 -0.0589509 0.52692 0.849198 -0.0349133 0.52692 0.849838 -0.0114849 0.52692 0.849838 0.0114847 0.52692 0.849198 0.0349134 0.52692 0.847868 0.0589509 0.52692 0.845794 0.0835913 0.52692 0.842919 0.108825 0.52692 0.839183 0.134638 0.52692 0.822181 0.215346 0.52692 0.814364 0.243241 0.52692 0.78352 0.329321 0.52692 0.780602 0.440553 0.443366 0.722647 0.447367 0.52692 0.727499 0.590031 0.350154 0.670526 0.594829 0.443366 0.696159 0.564614 0.443366 0.660102 0.53537 0.52692 0.609717 0.592115 0.52692 0.582376 0.681369 0.443366 0.549253 0.708341 0.443366 0.499076 0.792663 0.350154 0.439139 0.781398 0.443367 0.477576 0.758516 0.443367 0.452841 0.719229 0.52692 0.399079 0.802597 0.443367 0.357499 0.821961 0.443367 0.314521 0.839347 0.443367 0.270282 0.854619 0.443367 0.186703 0.917896 0.350155 0.17866 0.878355 0.443366 0.169407 0.832861 0.52692 0.0360796 0.895614 0.443366 -0.0120308 0.89626 0.443366 -0.0600892 0.894324 0.443366 -0.107889 0.889824 0.443366 -0.155227 0.882797 0.443366 -0.258891 0.900204 0.350154 -0.247739 0.861424 0.443366 -0.234907 0.816807 0.52692 -0.336177 0.83091 0.443366 -0.378472 0.812518 0.443366 -0.419306 0.792217 0.443367 -0.434815 0.730268 0.52692 -0.532004 0.721386 0.443367 -0.536728 0.658998 0.52692 -0.686586 0.637174 0.350155 -0.683575 0.579785 0.443366 -0.657009 0.609726 0.443367 -0.62298 0.578145 0.52692 -0.628565 0.639008 0.443367 -0.748338 0.402921 0.52692 -0.763519 0.373356 0.52692 -0.777211 0.343945 0.52692 -0.78948 0.314764 0.52692 -0.818417 0.229237 0.52692 -0.844113 0.301496 0.443366 -0.854261 0.271411 0.443366 -0.831829 0.174403 0.52692 -0.841163 0.12166 0.52692 -0.882691 0.155828 0.443367 -0.890588 0.101386 0.443367 -0.89319 0.0750851 0.443367 -0.8496 0.0231228 0.52692 -0.848623 0.0468562 0.52692 -1 -3.68545e-16 -2.04623e-07 -0.99963 -0.0272059 -2.04623e-07 -0.99546 2.74273e-19 0.0951823 -0.894977 -0.0494157 0.443367 -0.89319 -0.0750852 0.443367 -0.890588 -0.101386 0.443367 -0.88711 -0.128306 0.443367 -0.882691 -0.155828 0.443367 -0.954588 -0.16852 0.245689 -0.916759 -0.19221 0.350155 -0.922428 -0.162843 0.350155 -0.909967 -0.222154 0.350155 -0.948721 -0.198911 0.245689 -0.863122 -0.241758 0.443366 -0.870087 -0.346902 0.350154 -0.912867 -0.326053 0.245689 -0.900422 -0.358996 0.245689 -0.89085 -0.435621 0.128917 -0.813509 -0.527106 0.245689 -0.764072 -0.541836 0.350154 -0.786102 -0.509348 0.350154 -0.752238 -0.487406 0.443366 -0.708282 -0.54933 0.443366 -0.714348 -0.605886 0.350154 -0.679763 -0.691056 0.245689 -0.625173 -0.697532 0.350155 -0.656862 -0.667775 0.350155 -0.628566 -0.639008 0.443367 -0.591528 -0.726283 0.350155 -0.532004 -0.721386 0.443367 -0.47921 -0.804829 0.350155 -0.438183 -0.827881 0.350155 -0.39551 -0.849096 0.350155 -0.35131 -0.868316 0.350155 -0.267917 -0.931589 0.245689 -0.258891 -0.900204 0.350154 -0.247739 -0.861424 0.443366 -0.162215 -0.922539 0.350154 -0.112746 -0.929882 0.350154 -0.0627946 -0.934585 0.350154 -0.0125725 -0.936608 0.350154 0.037704 -0.935933 0.350154 0.0878175 -0.932566 0.350154 0.137554 -0.926537 0.350154 0.243261 -0.938329 0.245689 0.235066 -0.906717 0.350155 0.224939 -0.867657 0.443367 0.328679 -0.877133 0.350155 0.373593 -0.858964 0.350155 0.417045 -0.838728 0.350155 0.43914 -0.781398 0.443367 0.537456 -0.767159 0.350155 0.549253 -0.708341 0.443366 0.641263 -0.682769 0.350154 0.643022 -0.624458 0.443366 0.696159 -0.564614 0.443366 0.700712 -0.621607 0.350154 0.752356 -0.557989 0.350154 0.741919 -0.502974 0.443366 0.844183 -0.476436 0.245689 0.833318 -0.427752 0.350154 0.815743 -0.460386 0.350154 0.780602 -0.440553 0.443366 0.79742 -0.409325 0.443367 0.893623 -0.375599 0.245688 0.876282 -0.33094 0.350155 0.863517 -0.362945 0.350155 0.826318 -0.34731 0.443367 0.838533 -0.316683 0.443367 0.849353 -0.286403 0.443367 0.858848 -0.256527 0.443367 0.880109 -0.169808 0.443366 0.885022 -0.141993 0.443366 0.888962 -0.11477 0.443366 0.891995 -0.0881574 0.443366 0.894182 -0.062171 0.443366 0.895584 -0.0368203 0.443366 0.896259 -0.0121122 0.443366 0.896259 0.012112 0.443366 0.895584 0.0368205 0.443366 0.894182 0.062171 0.443366 0.891995 0.0881574 0.443366 0.888962 0.114769 0.443366 0.885022 0.141993 0.443367 0.945356 0.214333 0.245688 0.906126 0.237333 0.350155 0.913508 0.207112 0.350155 0.874155 0.19819 0.443367 0.867092 0.227109 0.443367 0.858848 0.256527 0.443367 0.887589 0.299296 0.350155 0.838533 0.316683 0.443367 0.826318 0.34731 0.443367 0.79742 0.409326 0.443366 0.84922 0.395243 0.350155 0.815743 0.460386 0.350155 0.76212 0.471804 0.443366 0.719946 0.533952 0.443366 0.775318 0.525617 0.350154 0.700711 0.621607 0.350154 0.643022 0.624459 0.443366 0.641263 0.682769 0.350154 0.608594 0.712043 0.350154 0.556194 0.793905 0.245689 0.537456 0.767159 0.350154 0.514304 0.73411 0.443366 0.458909 0.816575 0.350155 0.417045 0.838728 0.350155 0.373593 0.858964 0.350155 0.292297 0.924229 0.245689 0.235065 0.906717 0.350155 0.28245 0.893092 0.350155 0.243261 0.938329 0.245689 0.224939 0.867657 0.443367 0.137554 0.926537 0.350155 0.0878177 0.932566 0.350155 0.0377038 0.935933 0.350155 -0.0125724 0.936608 0.350154 -0.0627943 0.934585 0.350154 -0.112746 0.929882 0.350154 -0.218351 0.944436 0.245689 -0.210995 0.912619 0.350154 -0.201906 0.873304 0.443366 -0.305719 0.885397 0.350154 -0.351311 0.868316 0.350154 -0.39551 0.849096 0.350154 -0.495918 0.832888 0.245688 -0.518494 0.7801 0.350155 -0.47921 0.804829 0.350155 -0.458567 0.770158 0.443367 -0.555954 0.753861 0.350155 -0.566046 0.694995 0.443367 -0.625173 0.697532 0.350155 -0.765972 0.594074 0.245689 -0.740167 0.57406 0.350155 -0.834419 0.493338 0.245689 -0.656862 0.667775 0.350155 -0.805225 0.39375 0.443366 -0.819665 0.362733 0.443366 -0.832605 0.331957 0.443366 -0.870766 0.212584 0.443367 -0.863122 0.241758 0.443366 -0.901978 0.252642 0.350154 -0.892718 0.28363 0.350154 -0.882113 0.315069 0.350154 -0.877266 0.18393 0.443367 -0.88711 0.128306 0.443367 -0.922428 0.162843 0.350155 -0.930681 0.10595 0.350155 -0.9334 0.0784653 0.350155 -0.894977 0.0494157 0.443367 -0.896009 0.0243858 0.443367 -0.935267 -0.0516403 0.350155 -0.9334 -0.0784654 0.350155 -0.933424 -0.26145 0.245689 -0.941692 -0.2299 0.245689 -0.963362 -0.23519 0.128917 -0.945101 -0.300272 0.128917 -0.923842 -0.293518 0.245689 -0.954904 -0.267466 0.128917 -0.856565 -0.379062 0.350154 -0.765972 -0.594074 0.245689 -0.808906 -0.57363 0.128917 -0.783599 -0.607745 0.128917 -0.740167 -0.57406 0.350154 -0.686586 -0.637174 0.350155 -0.739253 -0.62701 0.245689 -0.646969 -0.721851 0.245689 -0.575337 -0.780144 0.245689 -0.626238 -0.7689 0.128917 -0.588576 -0.798097 0.128917 -0.555954 -0.753861 0.350155 -0.536571 -0.807297 0.245689 -0.495918 -0.832888 0.245689 -0.45346 -0.856745 0.245689 -0.409299 -0.878699 0.245689 -0.316378 -0.916265 0.245689 -0.371925 -0.919267 0.128917 -0.323659 -0.93735 0.128917 -0.30572 -0.885397 0.350154 -0.218351 -0.944436 0.245689 -0.16787 -0.954702 0.245689 -0.116677 -0.962301 0.245689 -0.0649839 -0.967168 0.245689 -0.0130109 -0.969261 0.245689 0.0390185 -0.968563 0.245689 0.0908792 -0.965079 0.245689 0.193213 -0.949898 0.245688 0.145625 -0.980905 0.128917 0.197659 -0.971757 0.128917 0.186703 -0.917896 0.350155 0.292297 -0.924229 0.245689 0.340139 -0.907713 0.245689 0.386618 -0.888911 0.245689 0.474908 -0.845044 0.245689 0.441516 -0.887944 0.128917 0.485837 -0.86449 0.128917 0.458909 -0.816575 0.350155 0.516475 -0.820299 0.245689 0.57398 -0.740229 0.350155 0.556194 -0.793905 0.245689 0.629812 -0.736868 0.245689 0.695398 -0.675322 0.245689 0.678891 -0.722833 0.128917 0.7114 -0.690862 0.128917 0.67197 -0.65257 0.350154 0.727499 -0.590031 0.350154 0.725141 -0.643279 0.245689 0.778586 -0.577443 0.245689 0.775318 -0.525617 0.350154 0.79643 -0.493043 0.350154 0.84922 -0.395243 0.350155 0.887589 -0.299296 0.350155 0.897512 -0.268076 0.350155 0.991769 -0.128042 1.91753e-07 0.979134 -0.157092 -0.128917 0.983493 -0.126974 -0.128917 0.913508 -0.207112 0.350155 0.91973 -0.177452 0.350155 0.924864 -0.148385 0.350155 0.928982 -0.119936 0.350155 0.93215 -0.092126 0.350155 0.934436 -0.0649698 0.350154 0.935901 -0.0384779 0.350154 0.936606 -0.0126575 0.350154 0.936606 0.0126573 0.350154 0.935901 0.0384781 0.350154 0.934436 0.0649698 0.350154 0.932151 0.0921261 0.350154 0.928982 0.119936 0.350154 0.924864 0.148385 0.350154 0.91973 0.177452 0.350154 0.897512 0.268076 0.350155 0.906833 0.342478 0.245689 0.939671 0.316858 0.128917 0.927701 0.350359 0.128917 0.876282 0.33094 0.350155 0.863517 0.362945 0.350155 0.833318 0.427753 0.350155 0.878828 0.409022 0.245689 0.79643 0.493043 0.350155 0.844183 0.476436 0.245689 0.752356 0.557989 0.350154 0.802349 0.543942 0.245689 0.752863 0.610602 0.245689 0.695398 0.675322 0.245689 0.741828 0.658082 0.128917 0.7114 0.690862 0.128917 0.67197 0.65257 0.350154 0.66362 0.706573 0.245689 0.57398 0.740229 0.350154 0.629812 0.736868 0.245689 0.516476 0.820299 0.245689 0.474908 0.845044 0.245688 0.431585 0.86797 0.245689 0.340139 0.907713 0.245689 0.395515 0.909367 0.128917 0.347966 0.928601 0.128917 0.32868 0.877132 0.350155 0.193213 0.949898 0.245689 0.14235 0.95884 0.245689 0.0908794 0.965079 0.245689 0.0390183 0.968563 0.245689 -0.0130107 0.969261 0.245689 -0.0649835 0.967168 0.245689 -0.16787 0.954702 0.245689 -0.119362 0.984446 0.128917 -0.171733 0.976672 0.128917 -0.162215 0.922539 0.350154 -0.267917 0.931589 0.245689 -0.316378 0.916265 0.245689 -0.363559 0.898589 0.245689 -0.45346 0.856745 0.245689 -0.418718 0.898919 0.128917 -0.463894 0.87646 0.128917 -0.438183 0.827881 0.350154 -0.536571 0.807297 0.245689 -0.612151 0.751604 0.245689 -0.588576 0.798097 0.128917 -0.626238 0.7689 0.128917 -0.591528 0.726283 0.350155 -0.646969 0.721851 0.245689 -0.714348 0.605886 0.350155 -0.786102 0.509348 0.350155 -0.923842 0.293518 0.245689 -0.912867 0.326053 0.245689 -0.933874 0.333556 0.128917 -0.841474 0.411476 0.350154 -0.856565 0.379062 0.350154 -0.870087 0.346902 0.350154 -0.948721 0.198911 0.245689 -0.954588 0.16852 0.245688 -0.909967 0.222154 0.350154 -0.916759 0.19221 0.350155 -0.927046 0.134082 0.350155 -0.935267 0.0516403 0.350155 -0.936345 0.0254836 0.350155 -0.940459 -5.34075e-16 -0.339908 -0.936345 -0.0254835 -0.350155 -0.964178 -3.5318e-16 -0.265255 -0.967875 -0.0534406 0.245689 -0.96899 -0.026372 -0.245689 -0.991288 -0.0269788 -0.128917 -0.982975 -5.4829e-16 -0.183742 -0.993582 -0.113111 1.91753e-07 -0.985291 -0.112167 0.128917 -0.996485 -0.0837686 -2.04623e-07 -0.989702 -0.143144 1.91753e-07 -0.981443 -0.14195 0.128917 -0.984772 -0.173849 1.91753e-07 -0.970553 -0.203488 0.128917 -0.976555 -0.172398 0.128917 -0.941732 -0.336363 1.91753e-07 -0.933874 -0.333556 0.128917 -0.953054 -0.302799 1.91753e-07 -0.873139 -0.470116 0.128917 -0.834419 -0.493338 0.245689 -0.85362 -0.504691 0.128917 -0.832229 -0.539235 0.128917 -0.79071 -0.560727 0.245689 -0.73299 -0.680239 -2.04623e-07 -0.726874 -0.674563 0.128917 -0.762629 -0.646836 -2.04623e-07 -0.710523 -0.659389 0.245688 -0.695406 -0.706959 0.128917 -0.661857 -0.738462 0.128917 -0.612151 -0.751604 0.245689 -0.548918 -0.825875 0.128917 -0.50733 -0.852055 0.128917 -0.422241 -0.906483 1.91753e-07 -0.418718 -0.898919 0.128917 -0.467798 -0.883835 1.91753e-07 -0.375054 -0.927003 1.91753e-07 -0.363558 -0.898589 0.245689 -0.274083 -0.953026 0.128917 -0.223376 -0.96617 0.128917 -0.171733 -0.976672 0.128917 -0.119362 -0.984446 0.128917 -0.0664793 -0.989425 0.128917 -0.0133103 -0.991566 0.128917 0.0937528 -0.995596 -2.04623e-07 0.0929705 -0.987288 0.128917 0.0402523 -0.99919 -2.04623e-07 0.146851 -0.989159 -2.04623e-07 0.14235 -0.95884 0.245689 0.248859 -0.959922 0.128917 0.299024 -0.945497 0.128917 0.347966 -0.928601 0.128917 0.445232 -0.895415 1.91753e-07 0.398843 -0.917019 1.91753e-07 0.431585 -0.86797 0.245689 0.528361 -0.839175 0.128917 0.612773 -0.790259 1.91753e-07 0.60766 -0.783664 0.128917 0.573781 -0.819009 1.91753e-07 0.593991 -0.766037 0.245689 0.644305 -0.753825 0.128917 0.66362 -0.706573 0.245689 0.776668 -0.62991 -2.04623e-07 0.770187 -0.624653 0.128917 0.74807 -0.663619 1.91753e-07 0.752863 -0.610602 0.245689 0.82772 -0.561142 -2.04623e-07 0.820813 -0.556459 0.128917 0.803206 -0.595702 -2.04623e-07 0.802349 -0.543942 0.245689 0.824196 -0.510233 0.245689 0.843163 -0.521974 0.128917 0.86361 -0.4874 0.128917 0.862371 -0.442666 0.245689 0.878827 -0.409023 0.245688 0.899051 -0.418435 0.128917 0.914187 -0.384242 0.128917 0.906833 -0.342478 0.245689 0.918534 -0.309731 0.245689 0.928802 -0.277422 0.245689 0.937718 -0.245607 0.245689 0.945356 -0.214333 0.245689 0.951795 -0.183639 0.245689 0.957109 -0.153558 0.245689 0.96137 -0.124118 0.245689 0.964649 -0.0953379 0.245689 0.967014 -0.0672349 0.245689 0.968531 -0.0398194 0.245689 0.96926 -0.0130988 0.245689 0.96926 0.0130986 0.245689 0.968531 0.0398196 0.245689 0.967014 0.0672349 0.245689 0.964649 0.095338 0.245689 0.96137 0.124118 0.245689 0.957109 0.153558 0.245689 0.951795 0.183639 0.245689 0.967369 0.253373 -2.04623e-07 0.959296 0.251259 0.128917 0.975249 0.22111 -2.04623e-07 0.937718 0.245607 0.245689 0.928802 0.277422 0.245689 0.918534 0.309731 0.245689 0.893623 0.375599 0.245689 0.88964 0.456663 1.91753e-07 0.882216 0.452852 0.128917 0.906616 0.421956 1.91753e-07 0.862371 0.442666 0.245689 0.850258 0.526366 1.91753e-07 0.843163 0.521974 0.128917 0.870877 0.491502 1.91753e-07 0.824196 0.510233 0.245689 0.803206 0.595702 1.91753e-07 0.796503 0.590731 0.128917 0.82772 0.561142 1.91753e-07 0.778586 0.577443 0.245689 0.770187 0.624653 0.128917 0.725141 0.643279 0.245689 0.678891 0.722833 0.128917 0.612773 0.790259 -2.04623e-07 0.60766 0.783664 0.128917 0.649726 0.760168 -2.04623e-07 0.593991 0.766036 0.245689 0.568993 0.812174 0.128917 0.528361 0.839175 0.128917 0.485837 0.86449 0.128917 0.398843 0.917019 -2.04623e-07 0.445232 0.895415 -2.04623e-07 0.386618 0.888911 0.245689 0.299024 0.945497 0.128917 0.248859 0.959922 0.128917 0.197659 0.971757 0.128917 0.145625 0.980905 0.128917 0.0929707 0.987288 0.128917 0.0399162 0.990852 0.128917 -0.0133101 0.991566 0.128917 -0.120366 0.99273 1.91753e-07 -0.0670383 0.99775 1.91753e-07 -0.116677 0.962301 0.245689 -0.223376 0.96617 0.128917 -0.274083 0.953026 0.128917 -0.323658 0.93735 0.128917 -0.371925 0.919267 0.128917 -0.409299 0.878699 0.245689 -0.50733 0.852055 0.128917 -0.548918 0.825875 0.128917 -0.575337 0.780144 0.245689 -0.661857 0.738462 0.128917 -0.726874 0.674562 0.128917 -0.739254 0.62701 0.245689 -0.756265 0.641438 0.128917 -0.783599 0.607744 0.128917 -0.79071 0.560727 0.245689 -0.853498 0.459541 0.245689 -0.870812 0.425822 0.245689 -0.886428 0.392278 0.245689 -0.900422 0.358996 0.245689 -0.933424 0.26145 0.245689 -0.941692 0.2299 0.245689 -0.945101 0.300273 0.128917 -0.959366 0.138757 0.245689 -0.963128 0.109644 0.245689 -0.976555 0.172398 0.128917 -0.965942 0.0812009 0.245689 -0.985291 0.112167 0.128917 -0.98817 0.0830695 0.128917 -0.96899 0.0263721 0.245689 -0.967875 0.0534407 0.245689 -0.990147 -0.0546704 0.128917 -0.98817 -0.0830696 0.128917 -0.971468 -0.237169 1.91753e-07 -0.97872 -0.205201 1.91753e-07 -0.970553 -0.203488 -0.128917 -0.96294 -0.269717 1.91753e-07 -0.963362 -0.23519 -0.128917 -0.933874 -0.333556 -0.128917 -0.898347 -0.439287 1.91753e-07 -0.880486 -0.474072 -2.04623e-07 -0.860803 -0.508938 -2.04623e-07 -0.839232 -0.543773 -2.04623e-07 -0.815713 -0.578457 -2.04623e-07 -0.790192 -0.612859 -2.04623e-07 -0.756265 -0.641439 0.128917 -0.701258 -0.712908 -2.04623e-07 -0.626238 -0.7689 -0.128917 -0.631507 -0.77537 -2.04623e-07 -0.661857 -0.738462 -0.128917 -0.593529 -0.804813 1.91753e-07 -0.553538 -0.832824 1.91753e-07 -0.463894 -0.87646 -0.128917 -0.50733 -0.852055 -0.128917 -0.463894 -0.87646 0.128917 -0.326382 -0.945238 1.91753e-07 -0.276389 -0.961046 1.91753e-07 -0.225256 -0.9743 1.91753e-07 -0.173178 -0.98489 1.91753e-07 -0.120366 -0.99273 -2.04623e-07 -0.0133103 -0.991566 -0.128917 -0.0134223 -0.99991 -2.04623e-07 -0.0664793 -0.989425 -0.128917 0.0399164 -0.990852 -0.128917 0.0399164 -0.990852 0.128917 0.199322 -0.979934 -2.04623e-07 0.250953 -0.967999 -2.04623e-07 0.30154 -0.953454 -2.04623e-07 0.395515 -0.909367 -0.128917 0.347966 -0.928601 -0.128917 0.395515 -0.909367 0.128917 0.489925 -0.871765 1.91753e-07 0.532807 -0.846237 1.91753e-07 0.568993 -0.812174 0.128917 0.649727 -0.760168 1.91753e-07 0.684604 -0.728915 1.91753e-07 0.717386 -0.696676 1.91753e-07 0.741828 -0.658082 0.128917 0.796503 -0.590731 0.128917 0.882216 -0.452852 -0.128917 0.88964 -0.456663 -2.04623e-07 0.86361 -0.4874 -0.128917 0.882216 -0.452852 0.128917 0.927701 -0.350359 -0.128917 0.935507 -0.353307 -2.04623e-07 0.914187 -0.384242 -0.128917 0.927701 -0.350359 0.128917 0.939671 -0.316858 0.128917 0.950176 -0.283806 0.128917 0.959296 -0.251259 0.128917 0.967111 -0.219265 0.128917 0.973698 -0.187865 0.128917 0.979134 -0.157092 0.128917 0.983493 -0.126974 0.128917 0.986847 -0.0975318 0.128917 0.989267 -0.0687821 0.128917 0.990818 -0.0407357 0.128917 0.991565 -0.0134002 0.128917 0.991565 0.0134 0.128917 0.990818 0.040736 0.128917 0.989267 0.0687822 0.128917 0.986847 0.0975319 0.128917 0.983493 0.126974 0.128917 0.979134 0.157092 0.128917 0.973698 0.187865 0.128917 0.967111 0.219265 0.128917 0.950176 0.283806 0.128917 0.947578 0.319525 1.91753e-07 0.935507 0.353307 1.91753e-07 0.914187 0.384242 0.128917 0.899051 0.418435 0.128917 0.86361 0.4874 0.128917 0.820813 0.556459 0.128917 0.776668 0.62991 1.91753e-07 0.74807 0.663619 1.91753e-07 0.717386 0.696676 -2.04623e-07 0.684604 0.728915 -2.04623e-07 0.644305 0.753825 0.128917 0.573781 0.819008 -2.04623e-07 0.532807 0.846237 -2.04623e-07 0.441516 0.887944 -0.128917 0.485837 0.86449 -0.128917 0.441516 0.887944 0.128917 0.350894 0.936415 -2.04623e-07 0.30154 0.953454 1.91753e-07 0.250953 0.967999 1.91753e-07 0.199322 0.979934 1.91753e-07 0.146851 0.989159 1.91753e-07 0.093753 0.995596 1.91753e-07 -0.0133101 0.991566 -0.128917 -0.0134221 0.99991 1.91753e-07 0.0399162 0.990852 -0.128917 -0.0664789 0.989425 -0.128917 -0.0664789 0.989425 0.128917 -0.173179 0.98489 1.91753e-07 -0.225256 0.9743 -2.04623e-07 -0.276389 0.961046 -2.04623e-07 -0.326382 0.945238 -2.04623e-07 -0.418718 0.898919 -0.128917 -0.422242 0.906483 -2.04623e-07 -0.371925 0.919267 -0.128917 -0.467798 0.883835 -2.04623e-07 -0.511599 0.859225 -2.04623e-07 -0.588576 0.798097 -0.128917 -0.593529 0.804813 -2.04623e-07 -0.548918 0.825875 -0.128917 -0.631508 0.77537 -2.04623e-07 -0.695406 0.706959 -0.128917 -0.701258 0.712908 1.91753e-07 -0.661857 0.738462 -0.128917 -0.732991 0.680239 1.91753e-07 -0.762629 0.646836 1.91753e-07 -0.790193 0.612859 1.91753e-07 -0.834419 0.493338 -0.245689 -0.853498 0.459541 -0.245689 -0.890851 0.435621 0.128917 -0.906827 0.401305 0.128917 -0.921142 0.367257 0.128917 -0.970553 0.203488 0.128917 -0.963362 0.23519 0.128917 -0.971468 0.237169 -2.04623e-07 -0.954904 0.267467 0.128917 -0.953054 0.302799 -2.04623e-07 -0.941732 0.336363 -2.04623e-07 -0.981443 0.14195 0.128917 -0.984772 0.173849 -2.04623e-07 -0.993582 0.113111 -2.04623e-07 -0.996485 0.0837686 1.91753e-07 -0.991288 0.0269789 0.128917 -0.990147 0.0546704 0.128917 -0.99546 -3.67164e-16 -0.0951771 -0.998479 -0.0551305 -2.04623e-07 -0.896009 -0.0243857 -0.443366 -0.91287 -9.5769e-18 -0.408251 -0.963128 -0.109644 -0.245689 -0.9334 -0.0784654 -0.350155 -0.930681 -0.10595 -0.350155 -0.927046 -0.134082 -0.350155 -0.959366 -0.138756 -0.245689 -0.892718 -0.28363 -0.350154 -0.923842 -0.293518 -0.245689 -0.901978 -0.252642 -0.350154 -0.85362 -0.504691 -0.128917 -0.853498 -0.459541 -0.245689 -0.834419 -0.493338 -0.245689 -0.808906 -0.57363 -0.128917 -0.813509 -0.527106 -0.245689 -0.79071 -0.560727 -0.245689 -0.783599 -0.607745 -0.128917 -0.756265 -0.641439 -0.128917 -0.726874 -0.674563 -0.128917 -0.695406 -0.706959 -0.128917 -0.667426 -0.744676 -2.04623e-07 -0.588576 -0.798097 -0.128917 -0.548918 -0.825875 -0.128917 -0.511599 -0.859225 1.91753e-07 -0.418718 -0.898919 -0.128917 -0.371925 -0.919267 -0.128917 -0.323659 -0.93735 -0.128917 -0.274083 -0.953026 -0.128917 -0.223376 -0.96617 -0.128917 -0.119362 -0.984446 -0.128917 -0.16787 -0.954702 -0.245689 -0.116677 -0.962301 -0.245689 -0.0649839 -0.967168 -0.245689 -0.0670387 -0.99775 -2.04623e-07 0.0929705 -0.987288 -0.128917 0.145625 -0.980905 -0.128917 0.197659 -0.971757 -0.128917 0.248859 -0.959922 -0.128917 0.292297 -0.924229 -0.245689 0.340139 -0.907713 -0.245689 0.350894 -0.936415 -2.04623e-07 0.441516 -0.887944 -0.128917 0.485837 -0.86449 -0.128917 0.568993 -0.812174 -0.128917 0.516476 -0.820299 -0.245688 0.556194 -0.793905 -0.245689 0.60766 -0.783665 -0.128917 0.678891 -0.722833 -0.128917 0.629812 -0.736868 -0.245689 0.66362 -0.706573 -0.245689 0.7114 -0.690862 -0.128917 0.741828 -0.658082 -0.128917 0.770187 -0.624653 -0.128917 0.796503 -0.590731 -0.128917 0.820813 -0.556459 -0.128917 0.850258 -0.526366 -2.04623e-07 0.870877 -0.491502 -2.04623e-07 0.906616 -0.421956 -2.04623e-07 0.92188 -0.387476 -2.04623e-07 0.947578 -0.319524 -2.04623e-07 0.958172 -0.286194 1.91753e-07 0.967369 -0.253373 1.91753e-07 0.975249 -0.22111 1.91753e-07 0.981891 -0.189445 1.91753e-07 0.987373 -0.158414 1.91753e-07 0.995152 -0.0983526 1.91753e-07 0.997592 -0.0693609 1.91753e-07 0.999156 -0.0410785 1.91753e-07 0.999909 -0.0135129 1.91753e-07 0.999909 0.0135128 -2.04623e-07 0.964649 0.095338 -0.245689 0.986847 0.0975319 -0.128917 0.967014 0.0672349 -0.245689 0.999156 0.0410787 -2.04623e-07 0.997592 0.0693609 -2.04623e-07 0.995152 0.0983526 -2.04623e-07 0.991769 0.128042 -2.04623e-07 0.987373 0.158414 -2.04623e-07 0.981891 0.189445 -2.04623e-07 0.967111 0.219265 -0.128917 0.959296 0.251259 -0.128917 0.958172 0.286194 -2.04623e-07 0.914187 0.384242 -0.128917 0.906833 0.342478 -0.245689 0.893623 0.375599 -0.245689 0.92188 0.387476 1.91753e-07 0.899051 0.418435 -0.128917 0.882216 0.452852 -0.128917 0.86361 0.4874 -0.128917 0.843163 0.521974 -0.128917 0.820813 0.556459 -0.128917 0.796503 0.590731 -0.128917 0.741828 0.658082 -0.128917 0.752863 0.610602 -0.245689 0.725141 0.643279 -0.245689 0.7114 0.690862 -0.128917 0.644305 0.753825 -0.128917 0.66362 0.706573 -0.245689 0.629812 0.736868 -0.245689 0.60766 0.783664 -0.128917 0.568993 0.812174 -0.128917 0.516476 0.820299 -0.245689 0.474908 0.845044 -0.245689 0.489925 0.871765 -2.04623e-07 0.395515 0.909367 -0.128917 0.347966 0.928601 -0.128917 0.299024 0.945497 -0.128917 0.248859 0.959922 -0.128917 0.197659 0.971757 -0.128917 0.0929707 0.987288 -0.128917 0.14235 0.95884 -0.245688 0.0908794 0.965079 -0.245689 0.0390183 0.968563 -0.245689 0.0402521 0.99919 1.91753e-07 -0.119362 0.984446 -0.128917 -0.171733 0.976672 -0.128917 -0.223376 0.96617 -0.128917 -0.274083 0.953026 -0.128917 -0.316378 0.916265 -0.245689 -0.363559 0.898589 -0.245689 -0.375055 0.927003 -2.04623e-07 -0.463894 0.87646 -0.128917 -0.50733 0.852055 -0.128917 -0.553537 0.832824 -2.04623e-07 -0.626238 0.7689 -0.128917 -0.667426 0.744676 1.91753e-07 -0.756265 0.641438 -0.128917 -0.710524 0.659389 -0.245688 -0.739254 0.62701 -0.245688 -0.808906 0.57363 -0.128917 -0.765972 0.594074 -0.245689 -0.79071 0.560727 -0.245689 -0.815713 0.578457 1.91753e-07 -0.928893 0.370348 -2.04623e-07 -0.906827 0.401305 -0.128917 -0.921142 0.367257 -0.128917 -0.898347 0.439287 1.91753e-07 -0.914457 0.404682 -2.04623e-07 -0.96294 0.269717 -2.04623e-07 -0.933874 0.333556 -0.128917 -0.945101 0.300273 -0.128917 -0.97872 0.205201 -2.04623e-07 -0.976555 0.172398 -0.128917 -0.954588 0.16852 -0.245689 -0.981443 0.14195 -0.128917 -0.989702 0.143144 -2.04623e-07 -0.985291 0.112167 -0.128917 -0.98817 0.0830695 -0.128917 -0.99963 0.027206 1.91753e-07 -0.998479 0.0551305 1.91753e-07 -0.812557 -4.97386e-16 -0.582882 -0.8496 -0.0231227 -0.52692 -0.848642 -1.61832e-16 -0.528968 -0.990147 -0.0546704 -0.128917 -0.98817 -0.0830696 -0.128917 -0.985291 -0.112167 -0.128917 -0.981443 -0.14195 -0.128917 -0.976555 -0.172398 -0.128917 -0.922428 -0.162843 -0.350155 -0.948721 -0.198911 -0.245688 -0.954588 -0.16852 -0.245689 -0.877266 -0.18393 -0.443366 -0.909967 -0.222154 -0.350154 -0.916759 -0.19221 -0.350155 -0.954904 -0.267466 -0.128917 -0.945101 -0.300272 -0.128917 -0.89085 -0.435621 -0.128917 -0.873139 -0.470116 -0.128917 -0.832229 -0.539235 -0.128917 -0.739253 -0.62701 -0.245689 -0.740167 -0.57406 -0.350155 -0.714348 -0.605886 -0.350155 -0.710523 -0.659389 -0.245689 -0.646969 -0.721851 -0.245689 -0.656862 -0.667775 -0.350155 -0.625173 -0.697532 -0.350155 -0.612151 -0.751604 -0.245689 -0.575337 -0.780144 -0.245689 -0.495918 -0.832888 -0.245688 -0.518494 -0.7801 -0.350155 -0.47921 -0.804829 -0.350155 -0.45346 -0.856745 -0.245688 -0.409299 -0.878699 -0.245689 -0.363558 -0.898589 -0.245689 -0.316378 -0.916265 -0.245689 -0.218351 -0.944436 -0.245689 -0.258891 -0.900204 -0.350154 -0.210995 -0.912619 -0.350154 -0.162215 -0.922539 -0.350154 -0.171733 -0.976672 -0.128917 -0.0130109 -0.969261 -0.245689 0.0390185 -0.968563 -0.245689 0.0908792 -0.965079 -0.245689 0.14235 -0.95884 -0.245689 0.193213 -0.949898 -0.245689 0.235066 -0.906717 -0.350155 0.28245 -0.893092 -0.350155 0.299024 -0.945497 -0.128917 0.386618 -0.888911 -0.245689 0.431585 -0.86797 -0.245689 0.474908 -0.845044 -0.245688 0.528361 -0.839175 -0.128917 0.593991 -0.766037 -0.245689 0.644305 -0.753825 -0.128917 0.725141 -0.643279 -0.245689 0.67197 -0.65257 -0.350154 0.700712 -0.621607 -0.350154 0.752863 -0.610602 -0.245689 0.79643 -0.493043 -0.350154 0.824196 -0.510233 -0.245689 0.775318 -0.525617 -0.350154 0.843163 -0.521974 -0.128917 0.844183 -0.476436 -0.245689 0.862371 -0.442666 -0.245689 0.899051 -0.418435 -0.128917 0.887589 -0.299296 -0.350155 0.918534 -0.309731 -0.245689 0.876282 -0.33094 -0.350155 0.939671 -0.316858 -0.128917 0.950176 -0.283806 -0.128917 0.959296 -0.251259 -0.128917 0.967111 -0.219265 -0.128917 0.973698 -0.187865 -0.128917 0.986847 -0.0975318 -0.128917 0.989267 -0.0687821 -0.128917 0.990818 -0.0407357 -0.128917 0.991565 -0.0134002 -0.128917 0.991565 0.0134 -0.128917 0.990818 0.040736 -0.128917 0.989267 0.0687822 -0.128917 0.983493 0.126974 -0.128917 0.979134 0.157092 -0.128917 0.973698 0.187865 -0.128917 0.897512 0.268076 -0.350155 0.928802 0.277422 -0.245689 0.906126 0.237333 -0.350155 0.950176 0.283806 -0.128917 0.939671 0.316858 -0.128917 0.927701 0.350359 -0.128917 0.878828 0.409022 -0.245688 0.862371 0.442666 -0.245688 0.844183 0.476436 -0.245689 0.824196 0.510233 -0.245689 0.802349 0.543942 -0.245689 0.778586 0.577443 -0.245689 0.770187 0.624653 -0.128917 0.695398 0.675322 -0.245689 0.678891 0.722833 -0.128917 0.593991 0.766036 -0.245689 0.537456 0.767159 -0.350155 0.499076 0.792663 -0.350155 0.528361 0.839175 -0.128917 0.431585 0.86797 -0.245689 0.386618 0.888911 -0.245689 0.340139 0.907713 -0.245689 0.292297 0.924229 -0.245689 0.193213 0.949898 -0.245688 0.235065 0.906717 -0.350155 0.186703 0.917896 -0.350155 0.137554 0.926537 -0.350154 0.145625 0.980905 -0.128917 -0.0130107 0.969261 -0.245689 -0.0649835 0.967168 -0.245689 -0.116677 0.962301 -0.245689 -0.16787 0.954702 -0.245689 -0.218351 0.944436 -0.245689 -0.258891 0.900204 -0.350154 -0.305719 0.885397 -0.350154 -0.323658 0.93735 -0.128917 -0.409299 0.878699 -0.245689 -0.45346 0.856745 -0.245689 -0.536571 0.807297 -0.245689 -0.47921 0.804829 -0.350155 -0.518494 0.7801 -0.350155 -0.575337 0.780144 -0.245689 -0.646969 0.721851 -0.245689 -0.591528 0.726283 -0.350155 -0.625173 0.697532 -0.350155 -0.679763 0.691056 -0.245689 -0.726874 0.674562 -0.128917 -0.783599 0.607744 -0.128917 -0.813509 0.527106 -0.245689 -0.890851 0.435621 -0.128917 -0.963362 0.23519 -0.128917 -0.954904 0.267467 -0.128917 -0.933424 0.26145 -0.245689 -0.923842 0.293518 -0.245689 -0.912867 0.326053 -0.245689 -0.970553 0.203488 -0.128917 -0.963128 0.109644 -0.245689 -0.965942 0.0812009 -0.245689 -0.990147 0.0546704 -0.128917 -0.991288 0.0269789 -0.128917 -0.967875 -0.0534406 -0.245689 -0.965942 -0.081201 -0.245689 -0.941692 -0.2299 -0.245688 -0.933424 -0.26145 -0.245689 -0.886428 -0.392278 -0.245689 -0.824744 -0.44406 -0.350154 -0.806308 -0.476718 -0.350154 -0.786102 -0.509348 -0.350154 -0.764072 -0.541836 -0.350154 -0.765972 -0.594074 -0.245689 -0.686586 -0.637174 -0.350155 -0.679763 -0.691056 -0.245689 -0.591528 -0.726283 -0.350155 -0.532004 -0.721386 -0.443366 -0.496158 -0.746494 -0.443366 -0.536571 -0.807297 -0.245689 -0.438183 -0.827882 -0.350154 -0.39551 -0.849096 -0.350154 -0.35131 -0.868316 -0.350154 -0.29255 -0.847255 -0.443366 -0.247739 -0.861424 -0.443366 -0.267917 -0.931589 -0.245689 -0.112746 -0.929882 -0.350154 -0.0627946 -0.934585 -0.350154 -0.0125725 -0.936608 -0.350154 0.037704 -0.935933 -0.350154 0.0878175 -0.932566 -0.350155 0.137554 -0.926537 -0.350155 0.17866 -0.878354 -0.443366 0.224939 -0.867657 -0.443366 0.243261 -0.938329 -0.245689 0.328679 -0.877133 -0.350155 0.373593 -0.858964 -0.350155 0.417045 -0.838728 -0.350155 0.499076 -0.792663 -0.350155 0.43914 -0.781398 -0.443366 0.477576 -0.758516 -0.443366 0.537456 -0.767159 -0.350154 0.582376 -0.681369 -0.443366 0.608594 -0.712043 -0.350154 0.549253 -0.708341 -0.443366 0.641263 -0.682769 -0.350154 0.695398 -0.675322 -0.245689 0.719946 -0.533952 -0.443366 0.752356 -0.557989 -0.350154 0.696159 -0.564614 -0.443366 0.778586 -0.577443 -0.245689 0.802349 -0.543942 -0.245689 0.812637 -0.378216 -0.443366 0.84922 -0.395243 -0.350155 0.79742 -0.409325 -0.443366 0.878827 -0.409023 -0.245689 0.893623 -0.375599 -0.245689 0.906833 -0.342478 -0.245689 0.928802 -0.277422 -0.245689 0.937718 -0.245607 -0.245689 0.945356 -0.214333 -0.245689 0.951795 -0.183639 -0.245688 0.957109 -0.153558 -0.245688 0.96137 -0.124118 -0.245689 0.964649 -0.0953379 -0.245689 0.967014 -0.0672349 -0.245689 0.968531 -0.0398194 -0.245689 0.96926 -0.0130988 -0.245689 0.96926 0.0130986 -0.245689 0.968531 0.0398196 -0.245689 0.96137 0.124118 -0.245689 0.932151 0.0921261 -0.350154 0.928982 0.119936 -0.350154 0.957109 0.153558 -0.245689 0.951795 0.183639 -0.245689 0.945356 0.214333 -0.245689 0.937718 0.245607 -0.245689 0.918534 0.309731 -0.245689 0.876282 0.33094 -0.350155 0.863517 0.362945 -0.350155 0.780602 0.440553 -0.443366 0.815743 0.460386 -0.350154 0.79742 0.409326 -0.443366 0.741919 0.502974 -0.443366 0.775318 0.525617 -0.350154 0.76212 0.471804 -0.443366 0.696159 0.564614 -0.443366 0.727499 0.590031 -0.350154 0.719946 0.533952 -0.443366 0.700711 0.621607 -0.350154 0.641263 0.682769 -0.350154 0.643022 0.624459 -0.443366 0.613638 0.653356 -0.443366 0.608594 0.712043 -0.350154 0.57398 0.740229 -0.350154 0.556194 0.793905 -0.245689 0.458909 0.816575 -0.350155 0.417045 0.838728 -0.350155 0.373593 0.858964 -0.350155 0.28245 0.893092 -0.350155 0.314521 0.839347 -0.443366 0.270282 0.854619 -0.443366 0.224939 0.867657 -0.443366 0.243261 0.938329 -0.245689 0.0878177 0.932566 -0.350154 0.0377038 0.935933 -0.350154 -0.0125724 0.936608 -0.350154 -0.0627943 0.934585 -0.350154 -0.112746 0.929882 -0.350154 -0.162215 0.922539 -0.350154 -0.201906 0.873304 -0.443366 -0.247739 0.861424 -0.443366 -0.267917 0.931589 -0.245689 -0.351311 0.868316 -0.350154 -0.39551 0.849096 -0.350154 -0.458567 0.770158 -0.443366 -0.419306 0.792217 -0.443366 -0.495917 0.832888 -0.245689 -0.555954 0.753861 -0.350155 -0.612151 0.751604 -0.245689 -0.656862 0.667775 -0.350155 -0.686586 0.637174 -0.350155 -0.714348 0.605886 -0.350155 -0.740167 0.57406 -0.350154 -0.764072 0.541836 -0.350154 -0.771573 0.456182 -0.443366 -0.886428 0.392278 -0.245689 -0.900422 0.358996 -0.245689 -0.806307 0.476718 -0.350154 -0.916759 0.19221 -0.350155 -0.922428 0.162843 -0.350155 -0.941692 0.2299 -0.245689 -0.882113 0.315069 -0.350154 -0.892718 0.28363 -0.350154 -0.948721 0.198911 -0.245689 -0.959366 0.138757 -0.245689 -0.930681 0.10595 -0.350155 -0.9334 0.0784653 -0.350155 -0.96899 0.0263721 -0.245689 -0.967875 0.0534407 -0.245689 -0.686794 -8.25697e-17 -0.726852 -0.740552 -0.0201548 -0.671697 -0.732029 -0 -0.681273 -0.935267 -0.0516403 -0.350155 -0.797813 -0.0217132 -0.602514 -0.773786 -1.65973e-16 -0.633447 -0.844461 -0.0961348 -0.52692 -0.890588 -0.101386 -0.443366 -0.846928 -0.0711962 -0.52692 -0.841163 -0.12166 -0.52692 -0.88711 -0.128306 -0.443366 -0.863122 -0.241758 -0.443366 -0.870766 -0.212584 -0.443366 -0.825666 -0.201574 -0.52692 -0.819665 -0.362733 -0.443366 -0.805225 -0.393751 -0.443366 -0.713276 -0.462161 -0.52692 -0.752238 -0.487406 -0.443366 -0.73161 -0.432554 -0.52692 -0.731156 -0.518495 -0.443366 -0.708282 -0.54933 -0.443366 -0.683575 -0.579786 -0.443366 -0.596009 -0.605911 -0.52692 -0.628566 -0.639008 -0.443366 -0.622979 -0.578146 -0.52692 -0.598241 -0.667483 -0.443366 -0.536728 -0.658999 -0.52692 -0.504449 -0.684022 -0.52692 -0.555954 -0.753861 -0.350155 -0.458567 -0.770158 -0.443366 -0.419306 -0.792217 -0.443366 -0.378472 -0.812518 -0.443366 -0.277397 -0.803372 -0.526919 -0.318764 -0.787874 -0.52692 -0.30572 -0.885397 -0.350154 -0.201906 -0.873304 -0.443366 -0.155227 -0.882797 -0.443366 -0.107889 -0.889824 -0.443366 -0.0600895 -0.894324 -0.443366 -0.0120309 -0.89626 -0.443366 0.0360798 -0.895614 -0.443366 0.0840345 -0.892393 -0.443366 0.124811 -0.840701 -0.52692 0.169407 -0.832861 -0.52692 0.186703 -0.917896 -0.350155 0.270282 -0.854619 -0.443366 0.31452 -0.839347 -0.443366 0.357499 -0.821961 -0.443366 0.416395 -0.740926 -0.52692 0.378409 -0.761027 -0.52692 0.458909 -0.816575 -0.350155 0.514303 -0.734111 -0.443366 0.57398 -0.740229 -0.350154 0.613638 -0.653356 -0.443366 0.643022 -0.624458 -0.443366 0.670526 -0.594829 -0.443366 0.727499 -0.590031 -0.350154 0.741919 -0.502974 -0.443366 0.76212 -0.471804 -0.443366 0.815743 -0.460386 -0.350155 0.833318 -0.427752 -0.350155 0.863517 -0.362945 -0.350155 0.814364 -0.243241 -0.52692 0.858848 -0.256527 -0.443366 0.805361 -0.271569 -0.52692 0.897512 -0.268076 -0.350155 0.906126 -0.237333 -0.350155 0.913508 -0.207112 -0.350155 0.91973 -0.177452 -0.350155 0.924864 -0.148385 -0.350154 0.928982 -0.119936 -0.350154 0.932151 -0.0921261 -0.350154 0.934436 -0.0649698 -0.350154 0.935901 -0.0384779 -0.350154 0.936606 -0.0126575 -0.350154 0.936606 0.0126573 -0.350154 0.935901 0.0384781 -0.350154 0.934436 0.0649698 -0.350154 0.834524 0.161013 -0.52692 0.78803 0.126431 -0.602514 0.783656 0.151198 -0.602514 0.924864 0.148385 -0.350155 0.91973 0.177452 -0.350155 0.913508 0.207112 -0.350155 0.805361 0.271569 -0.52692 0.849352 0.286403 -0.443366 0.814364 0.243241 -0.52692 0.887589 0.299296 -0.350155 0.770547 0.358627 -0.52692 0.812637 0.378216 -0.443366 0.78352 0.329321 -0.52692 0.84922 0.395243 -0.350155 0.833318 0.427753 -0.350154 0.79643 0.493043 -0.350154 0.752356 0.557989 -0.350154 0.670526 0.594829 -0.443366 0.67197 0.65257 -0.350154 0.582376 0.681369 -0.443366 0.487665 0.696088 -0.52692 0.514304 0.73411 -0.443366 0.520805 0.671653 -0.52692 0.477576 0.758516 -0.443366 0.439139 0.781398 -0.443366 0.399079 0.802597 -0.443366 0.338983 0.779388 -0.52692 0.29823 0.795873 -0.52692 0.32868 0.877132 -0.350155 0.17866 0.878355 -0.443366 0.131628 0.886623 -0.443366 0.0840346 0.892393 -0.443366 0.0360796 0.895614 -0.443366 -0.0120308 0.89626 -0.443366 -0.0600892 0.894324 -0.443366 -0.102301 0.843736 -0.52692 -0.147187 0.837073 -0.52692 -0.155227 0.882797 -0.443366 -0.191448 0.828072 -0.52692 -0.210995 0.912619 -0.350154 -0.292549 0.847255 -0.443366 -0.336177 0.83091 -0.443366 -0.378472 0.812518 -0.443366 -0.438183 0.827881 -0.350155 -0.496158 0.746494 -0.443366 -0.536728 0.658998 -0.52692 -0.566046 0.694995 -0.443366 -0.504449 0.684022 -0.52692 -0.598241 0.667483 -0.443366 -0.62298 0.578145 -0.52692 -0.657009 0.609726 -0.443366 -0.596009 0.605911 -0.52692 -0.671597 0.520878 -0.52692 -0.708282 0.54933 -0.443366 -0.64817 0.549756 -0.52692 -0.713276 0.462161 -0.526919 -0.752238 0.487406 -0.443366 -0.693287 0.491639 -0.52692 -0.786102 0.509348 -0.350154 -0.870087 0.346902 -0.350154 -0.901978 0.252642 -0.350155 -0.909967 0.222154 -0.350155 -0.854261 0.271411 -0.443366 -0.844113 0.301496 -0.443366 -0.927046 0.134082 -0.350155 -0.882691 0.155828 -0.443366 -0.890588 0.101386 -0.443366 -0.89319 0.0750851 -0.443366 -0.936345 0.0254836 -0.350155 -0.935267 0.0516403 -0.350155 -0.882128 -1.77917e-16 -0.47101 -0.894977 -0.0494157 -0.443366 -0.89319 -0.0750852 -0.443366 -0.882691 -0.155828 -0.443366 -0.785955 -0.13875 -0.602514 -0.831829 -0.174403 -0.52692 -0.836973 -0.147757 -0.52692 -0.76853 -0.215263 -0.602514 -0.702723 -0.378361 -0.602514 -0.748338 -0.402921 -0.52692 -0.716978 -0.350598 -0.602514 -0.789215 -0.42493 -0.443366 -0.771573 -0.456181 -0.443366 -0.630659 -0.489128 -0.602514 -0.671597 -0.520878 -0.52692 -0.651027 -0.461671 -0.602514 -0.64817 -0.549756 -0.52692 -0.657009 -0.609726 -0.443366 -0.567256 -0.632911 -0.52692 -0.566046 -0.694995 -0.443366 -0.47046 -0.70783 -0.52692 -0.434815 -0.730268 -0.52692 -0.397589 -0.751185 -0.52692 -0.336994 -0.723472 -0.602514 -0.299334 -0.739849 -0.602514 -0.336176 -0.83091 -0.443366 -0.234907 -0.816808 -0.526919 -0.191448 -0.828072 -0.52692 -0.147187 -0.837073 -0.52692 -0.102301 -0.843736 -0.52692 -0.0569772 -0.848003 -0.52692 -0.0114078 -0.849838 -0.52692 0.0321257 -0.797462 -0.602514 0.0748249 -0.794593 -0.602514 0.079682 -0.846172 -0.52692 0.117203 -0.789456 -0.602514 0.131628 -0.886623 -0.443366 0.213289 -0.822717 -0.52692 0.256283 -0.810355 -0.52692 0.29823 -0.795873 -0.52692 0.31832 -0.731881 -0.602514 0.355343 -0.714638 -0.602514 0.399079 -0.802597 -0.443366 0.45284 -0.71923 -0.52692 0.45794 -0.653657 -0.602514 0.489059 -0.630712 -0.602514 0.520805 -0.671653 -0.52692 0.552212 -0.646078 -0.526919 0.546388 -0.581753 -0.602514 0.572552 -0.556023 -0.602514 0.609718 -0.592115 -0.526919 0.635796 -0.56402 -0.52692 0.660102 -0.53537 -0.52692 0.682657 -0.506296 -0.52692 0.695054 -0.392272 -0.602514 0.740171 -0.417735 -0.52692 0.678598 -0.420097 -0.602514 0.780602 -0.440553 -0.443366 0.756118 -0.388125 -0.52692 0.770547 -0.358627 -0.52692 0.826318 -0.34731 -0.443366 0.838533 -0.316683 -0.443366 0.849353 -0.286403 -0.443366 0.867092 -0.227109 -0.443366 0.874155 -0.19819 -0.443366 0.880109 -0.169808 -0.443366 0.885022 -0.141993 -0.443366 0.888962 -0.11477 -0.443366 0.891995 -0.0881574 -0.443366 0.894182 -0.062171 -0.443366 0.895584 -0.0368203 -0.443366 0.896259 -0.0121122 -0.443366 0.896259 0.012112 -0.443366 0.895584 0.0368205 -0.443366 0.894182 0.062171 -0.443366 0.891995 0.0881574 -0.443366 0.888962 0.114769 -0.443366 0.885022 0.141993 -0.443366 0.880109 0.169808 -0.443366 0.874155 0.19819 -0.443366 0.867092 0.227109 -0.443366 0.858848 0.256527 -0.443366 0.838533 0.316683 -0.443366 0.826318 0.34731 -0.443366 0.756118 0.388125 -0.52692 0.740171 0.417735 -0.52692 0.722647 0.447367 -0.526919 0.703492 0.476923 -0.526919 0.682657 0.506296 -0.526919 0.660102 0.53537 -0.52692 0.597041 0.52964 -0.602514 0.572552 0.556023 -0.602514 0.609717 0.592115 -0.52692 0.581855 0.619516 -0.52692 0.518552 0.606696 -0.602514 0.489059 0.630712 -0.602514 0.549253 0.708341 -0.443366 0.452841 0.719229 -0.52692 0.416394 0.740926 -0.52692 0.355343 0.714638 -0.602514 0.31832 0.731881 -0.602514 0.357499 0.821961 -0.443366 0.256283 0.810355 -0.52692 0.213288 0.822717 -0.52692 0.169407 0.832861 -0.52692 0.124811 0.840701 -0.52692 0.0796821 0.846172 -0.52692 0.0342109 0.849226 -0.52692 -0.0107123 0.798036 -0.602514 -0.0535039 0.796313 -0.602514 -0.0569769 0.848003 -0.526919 -0.0960653 0.792306 -0.602514 -0.107889 0.889824 -0.443366 -0.234907 0.816807 -0.52692 -0.277397 0.803372 -0.52692 -0.318765 0.787874 -0.52692 -0.336994 0.723472 -0.602514 -0.373354 0.705396 -0.602514 -0.397589 0.751185 -0.52692 -0.434815 0.730268 -0.52692 -0.47046 0.70783 -0.52692 -0.532004 0.721386 -0.443366 -0.567256 0.632911 -0.52692 -0.628566 0.639008 -0.443366 -0.683575 0.579785 -0.443366 -0.731156 0.518495 -0.443366 -0.73161 0.432554 -0.526919 -0.748338 0.402921 -0.52692 -0.763519 0.373356 -0.52692 -0.863122 0.241758 -0.443366 -0.870766 0.212584 -0.443366 -0.810015 0.257354 -0.52692 -0.800393 0.28588 -0.52692 -0.877266 0.18393 -0.443366 -0.88711 0.128306 -0.443366 -0.836973 0.147757 -0.52692 -0.844461 0.0961347 -0.52692 -0.846928 0.0711962 -0.52692 -0.896009 0.0243858 -0.443366 -0.894977 0.0494157 -0.443366 -0.848623 -0.0468562 -0.52692 -0.60592 -0.0164907 -0.795355 -0.677048 -0.0184265 -0.735709 -0.637357 1.28778e-16 -0.770569 -0.736072 -0.0837956 -0.671697 -0.674918 -0.0567363 -0.735709 -0.672952 -0.0766099 -0.735709 -0.662885 -0.138982 -0.735709 -0.719689 -0.175701 -0.671697 -0.725061 -0.152018 -0.671697 -0.818417 -0.229236 -0.52692 -0.741357 -0.295577 -0.602514 -0.777211 -0.343945 -0.52692 -0.763519 -0.373357 -0.52692 -0.687014 -0.406187 -0.602514 -0.669798 -0.43399 -0.602514 -0.693287 -0.491639 -0.52692 -0.564975 -0.479193 -0.671697 -0.543018 -0.503939 -0.671697 -0.585006 -0.542904 -0.602514 -0.55968 -0.568978 -0.602514 -0.494447 -0.551675 -0.671697 -0.467837 -0.574414 -0.671697 -0.504011 -0.618829 -0.602514 -0.4737 -0.642327 -0.602514 -0.441783 -0.664684 -0.602514 -0.408311 -0.685754 -0.602514 -0.346557 -0.654768 -0.671697 -0.312807 -0.671546 -0.671697 -0.358869 -0.770434 -0.52692 -0.260488 -0.754402 -0.602514 -0.220588 -0.767019 -0.602514 -0.179778 -0.777597 -0.602514 -0.138215 -0.786049 -0.602514 -0.0960654 -0.792306 -0.602514 -0.049664 -0.739159 -0.671697 -0.00994356 -0.740759 -0.671697 -0.0107124 -0.798036 -0.602514 0.02982 -0.740226 -0.671697 0.0342111 -0.849226 -0.52692 0.159081 -0.782093 -0.602514 0.200288 -0.772568 -0.602514 0.240661 -0.760959 -0.602514 0.280051 -0.747361 -0.602514 0.338983 -0.779388 -0.52692 0.391013 -0.695762 -0.602514 0.425237 -0.675389 -0.602514 0.487665 -0.696088 -0.52692 0.518552 -0.606696 -0.602514 0.581855 -0.619516 -0.526919 0.55419 -0.491626 -0.671697 0.575376 -0.466653 -0.671697 0.619865 -0.502736 -0.602514 0.595036 -0.441311 -0.671697 0.613196 -0.415709 -0.671697 0.66061 -0.447852 -0.602514 0.703491 -0.476923 -0.52692 0.722647 -0.447367 -0.52692 0.682953 -0.287052 -0.671697 0.73576 -0.309248 -0.602514 0.671645 -0.312596 -0.671697 0.78352 -0.329322 -0.52692 0.795102 -0.300281 -0.52692 0.716652 -0.187705 -0.671697 0.772065 -0.202219 -0.602514 0.709838 -0.21202 -0.671697 0.822181 -0.215346 -0.52692 0.828879 -0.187925 -0.52692 0.834524 -0.161013 -0.52692 0.839183 -0.134638 -0.52692 0.842919 -0.108825 -0.52692 0.845795 -0.0835913 -0.526919 0.847868 -0.0589509 -0.526919 0.849198 -0.0349133 -0.526919 0.849837 -0.0114849 -0.52692 0.849837 0.0114847 -0.52692 0.849198 0.0349134 -0.52692 0.847868 0.0589509 -0.52692 0.845794 0.0835913 -0.52692 0.842919 0.108825 -0.52692 0.839183 0.134638 -0.52692 0.828879 0.187925 -0.52692 0.822181 0.215346 -0.52692 0.764725 0.228414 -0.602514 0.75627 0.255015 -0.602514 0.795102 0.300281 -0.52692 0.73576 0.309247 -0.602514 0.723578 0.336766 -0.602514 0.645168 0.364117 -0.671697 0.629893 0.389946 -0.671697 0.678598 0.420097 -0.602514 0.613196 0.415708 -0.671697 0.595036 0.441311 -0.671697 0.641045 0.475435 -0.602514 0.619866 0.502736 -0.602514 0.635796 0.56402 -0.52692 0.546388 0.581753 -0.602514 0.552212 0.646078 -0.52692 0.45794 0.653657 -0.602514 0.425238 0.675389 -0.602514 0.362949 0.645826 -0.671697 0.329839 0.663347 -0.671697 0.378409 0.761027 -0.52692 0.280052 0.747361 -0.602514 0.240661 0.760959 -0.602514 0.200287 0.772568 -0.602514 0.159081 0.782093 -0.602514 0.117203 0.789456 -0.602514 0.0694547 0.737563 -0.671697 0.0298198 0.740226 -0.671697 0.0321255 0.797461 -0.602514 -0.00994344 0.740759 -0.671697 -0.0114076 0.849839 -0.526919 -0.138215 0.786049 -0.602514 -0.179778 0.777597 -0.602514 -0.220588 0.767019 -0.602514 -0.260488 0.754402 -0.602514 -0.27785 0.686748 -0.671697 -0.312807 0.671546 -0.671697 -0.358869 0.770434 -0.52692 -0.408311 0.685754 -0.602514 -0.410075 0.616978 -0.671697 -0.439702 0.596226 -0.671697 -0.4737 0.642328 -0.602514 -0.504011 0.618829 -0.602514 -0.494447 0.551675 -0.671697 -0.51951 0.528141 -0.671697 -0.559679 0.568978 -0.602514 -0.585006 0.542904 -0.602514 -0.608661 0.516245 -0.602514 -0.630659 0.489127 -0.602514 -0.651027 0.461671 -0.602514 -0.669798 0.43399 -0.602514 -0.652287 0.351205 -0.671697 -0.665519 0.325435 -0.671697 -0.687014 0.406188 -0.602514 -0.818417 0.229237 -0.52692 -0.825666 0.201574 -0.52692 -0.751604 0.268454 -0.602514 -0.760641 0.241667 -0.602514 -0.831829 0.174403 -0.52692 -0.841163 0.12166 -0.52692 -0.795303 0.0668564 -0.602514 -0.848623 0.0468562 -0.52692 -0.792986 0.0902747 -0.602514 -0.8496 0.0231228 -0.52692 -0.452944 2.51061e-17 -0.891539 -0.525217 -0.0142943 -0.850848 -0.5218 -8.88038e-17 -0.853068 -0.796895 -0.0440001 -0.602514 -0.795303 -0.0668564 -0.602514 -0.792986 -0.0902749 -0.602514 -0.789889 -0.114244 -0.602514 -0.602254 -0.0685616 -0.795355 -0.599902 -0.0867659 -0.795355 -0.670323 -0.0969512 -0.735709 -0.781124 -0.163772 -0.602514 -0.775337 -0.189287 -0.602514 -0.629138 -0.250836 -0.735709 -0.61936 -0.27409 -0.735709 -0.677454 -0.299799 -0.671697 -0.729836 -0.32298 -0.602514 -0.665519 -0.325435 -0.671697 -0.652287 -0.351205 -0.671697 -0.637705 -0.377034 -0.671697 -0.621725 -0.402841 -0.671697 -0.604301 -0.428536 -0.671697 -0.585395 -0.454022 -0.671697 -0.60866 -0.516245 -0.602514 -0.51951 -0.528141 -0.671697 -0.532678 -0.594332 -0.602514 -0.439702 -0.596226 -0.671697 -0.410075 -0.616978 -0.671697 -0.346505 -0.581951 -0.735709 -0.316839 -0.59862 -0.735709 -0.373353 -0.705396 -0.602514 -0.27785 -0.686748 -0.671697 -0.241792 -0.700257 -0.671697 -0.204756 -0.711968 -0.671697 -0.166875 -0.721786 -0.671697 -0.117293 -0.667065 -0.735708 -0.0815239 -0.672374 -0.735708 -0.0891705 -0.73544 -0.671697 -0.0454052 -0.675775 -0.735708 -0.0535041 -0.796313 -0.602514 0.0694545 -0.737563 -0.671697 0.108791 -0.732794 -0.671697 0.147663 -0.725961 -0.671697 0.185912 -0.717119 -0.671697 0.204232 -0.645772 -0.735709 0.23766 -0.634232 -0.735709 0.259951 -0.693721 -0.671697 0.270136 -0.621095 -0.735709 0.295473 -0.679352 -0.671697 0.329839 -0.663347 -0.671697 0.362949 -0.645826 -0.671697 0.360869 -0.573155 -0.735709 0.388621 -0.554713 -0.735709 0.425072 -0.606743 -0.671697 0.453958 -0.585444 -0.671697 0.481334 -0.563152 -0.671697 0.507172 -0.539999 -0.671697 0.531458 -0.516115 -0.671697 0.597041 -0.52964 -0.602514 0.641045 -0.475435 -0.602514 0.629893 -0.389946 -0.671697 0.645168 -0.364117 -0.671697 0.710029 -0.364466 -0.602514 0.723578 -0.336767 -0.602514 0.746636 -0.281977 -0.602514 0.75627 -0.255015 -0.602514 0.764725 -0.228414 -0.602514 0.778354 -0.17647 -0.602514 0.783655 -0.151198 -0.602514 0.78803 -0.126431 -0.602514 0.791539 -0.102192 -0.602514 0.794239 -0.078496 -0.602514 0.796186 -0.0553575 -0.602514 0.797435 -0.0327851 -0.602514 0.798035 -0.0107848 -0.602514 0.798035 0.0107846 -0.602514 0.797435 0.0327853 -0.602514 0.796186 0.0553575 -0.602514 0.794239 0.078496 -0.602514 0.791539 0.102192 -0.602514 0.660534 0.149757 -0.735709 0.591141 0.134024 -0.795355 0.655197 0.171609 -0.735709 0.778354 0.17647 -0.602514 0.772065 0.202219 -0.602514 0.641793 0.216413 -0.735709 0.633618 0.239294 -0.735709 0.693048 0.261739 -0.671697 0.746636 0.281977 -0.602514 0.61405 0.28579 -0.735709 0.602551 0.309297 -0.735709 0.659068 0.338308 -0.671697 0.710029 0.364467 -0.602514 0.695054 0.392271 -0.602514 0.66061 0.447852 -0.602514 0.526036 0.426637 -0.735709 0.506667 0.449468 -0.735708 0.55419 0.491627 -0.671697 0.531458 0.516115 -0.671697 0.463681 0.493693 -0.735708 0.440059 0.514861 -0.735709 0.481334 0.563152 -0.671697 0.453958 0.585444 -0.671697 0.425072 0.606743 -0.671697 0.360869 0.573155 -0.735709 0.331825 0.590445 -0.735709 0.391013 0.695763 -0.602514 0.295473 0.679352 -0.671697 0.259952 0.693721 -0.671697 0.223388 0.706343 -0.671697 0.185912 0.717119 -0.671697 0.135001 0.663708 -0.735709 0.0994617 0.669955 -0.735709 0.108791 0.732794 -0.671697 0.0634987 0.674315 -0.735709 0.074825 0.794593 -0.602514 -0.0496637 0.739159 -0.671697 -0.0891704 0.73544 -0.671697 -0.128295 0.729632 -0.671697 -0.166875 0.721786 -0.671697 -0.204756 0.711968 -0.671697 -0.221058 0.640208 -0.735709 -0.254024 0.627857 -0.735709 -0.299334 0.739849 -0.602514 -0.346557 0.654768 -0.671697 -0.379006 0.636536 -0.671697 -0.441783 0.664684 -0.602514 -0.467837 0.574414 -0.671697 -0.532678 0.594332 -0.602514 -0.543018 0.503939 -0.671697 -0.564975 0.479193 -0.671697 -0.585395 0.454022 -0.671697 -0.604301 0.428536 -0.671697 -0.621725 0.402841 -0.671697 -0.702723 0.378361 -0.602514 -0.645502 0.205085 -0.735709 -0.652197 0.182679 -0.735709 -0.637705 0.377034 -0.671697 -0.76853 0.215264 -0.602514 -0.775337 0.189287 -0.602514 -0.706047 0.224322 -0.671697 -0.69766 0.249187 -0.671697 -0.785955 0.13875 -0.602514 -0.781125 0.163772 -0.602514 -0.789889 0.114245 -0.602514 -0.729545 0.128792 -0.671697 -0.736072 0.0837955 -0.671697 -0.738222 0.0620579 -0.671697 -0.796894 0.0440001 -0.602514 -0.797813 0.0217133 -0.602514 -0.739699 -0.0408421 -0.671697 -0.738222 -0.062058 -0.671697 -0.733197 -0.106045 -0.671697 -0.729545 -0.128792 -0.671697 -0.69766 -0.249186 -0.671697 -0.688148 -0.274363 -0.671697 -0.583021 -0.344703 -0.735708 -0.596352 -0.321088 -0.735708 -0.533702 -0.287356 -0.795355 -0.552481 -0.391788 -0.735709 -0.568411 -0.368297 -0.735709 -0.508696 -0.329605 -0.795355 -0.535196 -0.415088 -0.735709 -0.516527 -0.438101 -0.735709 -0.496453 -0.460725 -0.735709 -0.452047 -0.504368 -0.735709 -0.474961 -0.482851 -0.735709 -0.425063 -0.432125 -0.795355 -0.427719 -0.525157 -0.735709 -0.401996 -0.545098 -0.735709 -0.37491 -0.56407 -0.735709 -0.335524 -0.504812 -0.795355 -0.379006 -0.636536 -0.671697 -0.285983 -0.61396 -0.735709 -0.254024 -0.627857 -0.735709 -0.221058 -0.640208 -0.735709 -0.152565 -0.659891 -0.735709 -0.187198 -0.650915 -0.735709 -0.167532 -0.582532 -0.795355 -0.136537 -0.590566 -0.795355 -0.128295 -0.729632 -0.671697 -0.00909088 -0.677237 -0.735709 0.0272628 -0.676749 -0.735709 0.0634986 -0.674315 -0.735709 0.0994617 -0.669955 -0.735709 0.135001 -0.663708 -0.735709 0.16997 -0.655624 -0.735709 0.152114 -0.586747 -0.795355 0.223389 -0.706343 -0.671697 0.301555 -0.606463 -0.735709 0.331825 -0.590445 -0.735709 0.394717 -0.626914 -0.671697 0.41503 -0.535241 -0.735709 0.463681 -0.493693 -0.735709 0.440059 -0.51486 -0.735709 0.393828 -0.460772 -0.795355 0.485884 -0.471857 -0.735709 0.506667 -0.449468 -0.735709 0.526036 -0.426637 -0.735708 0.54401 -0.403468 -0.735708 0.560613 -0.38006 -0.735709 0.575878 -0.356507 -0.735709 0.589843 -0.332893 -0.735709 0.659068 -0.338308 -0.671697 0.61405 -0.28579 -0.735709 0.624388 -0.262437 -0.735709 0.693048 -0.261739 -0.671697 0.70199 -0.236712 -0.671697 0.595168 -0.114831 -0.795355 0.515897 -0.0995369 -0.850848 0.59849 -0.0960216 -0.795355 0.72249 -0.163804 -0.671697 0.72741 -0.140346 -0.671697 0.731471 -0.117357 -0.671697 0.734728 -0.0948571 -0.671697 0.737234 -0.0728621 -0.671697 0.739042 -0.0513844 -0.671697 0.740201 -0.030432 -0.671697 0.740758 -0.0100107 -0.671697 0.740758 0.0100106 -0.671697 0.740201 0.0304322 -0.671697 0.739042 0.0513844 -0.671697 0.737234 0.0728621 -0.671697 0.734728 0.094857 -0.671697 0.731471 0.117357 -0.671697 0.72741 0.140346 -0.671697 0.72249 0.163804 -0.671697 0.716652 0.187705 -0.671697 0.709838 0.21202 -0.671697 0.70199 0.236712 -0.671697 0.682953 0.287052 -0.671697 0.671645 0.312596 -0.671697 0.589843 0.332893 -0.735709 0.575878 0.356507 -0.735709 0.560613 0.38006 -0.735709 0.54401 0.403468 -0.735709 0.575376 0.466653 -0.671697 0.485885 0.471857 -0.735708 0.507172 0.539999 -0.671697 0.41503 0.535241 -0.735709 0.388621 0.554713 -0.735709 0.347794 0.496437 -0.795355 0.394717 0.626914 -0.671697 0.301555 0.606463 -0.735709 0.270136 0.621095 -0.735709 0.23766 0.634232 -0.735709 0.204232 0.645772 -0.735709 0.16997 0.655624 -0.735709 0.152114 0.586747 -0.795355 0.147663 0.725961 -0.671697 0.0272627 0.676749 -0.735709 -0.00909076 0.677237 -0.735709 -0.0454049 0.675775 -0.735709 -0.0815238 0.672374 -0.735709 -0.117294 0.667065 -0.735708 -0.152565 0.659892 -0.735708 -0.187198 0.650915 -0.735708 -0.167532 0.582532 -0.795355 -0.241792 0.700257 -0.671697 -0.285983 0.61396 -0.735709 -0.316839 0.59862 -0.735709 -0.37491 0.56407 -0.735709 -0.346505 0.581951 -0.735709 -0.310103 0.520814 -0.795355 -0.401996 0.545098 -0.735709 -0.427719 0.525157 -0.735709 -0.452047 0.504368 -0.735709 -0.474961 0.482851 -0.735709 -0.516527 0.438101 -0.735709 -0.496453 0.460725 -0.735709 -0.444298 0.412323 -0.795355 -0.552481 0.391788 -0.735709 -0.535196 0.415088 -0.735709 -0.478971 0.371481 -0.795355 -0.583021 0.344703 -0.735709 -0.568411 0.368297 -0.735709 -0.508696 0.329605 -0.795355 -0.608449 0.297528 -0.735709 -0.713371 0.199814 -0.671697 -0.719689 0.175701 -0.671697 -0.725061 0.152018 -0.671697 -0.733197 0.106045 -0.671697 -0.666985 0.117747 -0.735709 -0.672952 0.0766098 -0.735709 -0.674918 0.0567363 -0.735708 -0.740552 0.0201549 -0.671697 -0.739699 0.0408421 -0.671697 -0.0625688 -4.981e-17 -0.998041 -0.056897 -0.00154851 -0.998379 -0.180587 -5.50038e-17 -0.983559 -0.676268 -0.0373398 -0.735709 -0.324982 -0.00884469 -0.945679 -0.28421 -1.14944e-16 -0.958762 -0.200187 -0.00544828 -0.979743 -0.666985 -0.117747 -0.735709 -0.517411 -0.0913421 -0.850848 -0.426059 -0.0752151 -0.901563 -0.514231 -0.107815 -0.850848 -0.637834 -0.227818 -0.735709 -0.480467 -0.212625 -0.850848 -0.544528 -0.266271 -0.795355 -0.554293 -0.245296 -0.795355 -0.608449 -0.297528 -0.735708 -0.415176 -0.322003 -0.850848 -0.462263 -0.392076 -0.795355 -0.478971 -0.371481 -0.795355 -0.404557 -0.451381 -0.795355 -0.311847 -0.422858 -0.850848 -0.359764 -0.487833 -0.795355 -0.310103 -0.520814 -0.795355 -0.283553 -0.535732 -0.795355 -0.197058 -0.487058 -0.850848 -0.197835 -0.57295 -0.795355 -0.227337 -0.561897 -0.795355 -0.171485 -0.496639 -0.850848 -0.104971 -0.596986 -0.795355 -0.0729594 -0.601737 -0.795355 -0.0406351 -0.604781 -0.795355 -0.00813583 -0.60609 -0.795355 0.0243987 -0.605653 -0.795355 0.0568277 -0.603474 -0.795355 0.104726 -0.514869 -0.850848 0.120818 -0.593981 -0.795355 0.182777 -0.57793 -0.795355 0.212692 -0.567603 -0.795355 0.241756 -0.555846 -0.795355 0.257412 -0.458035 -0.850848 0.322958 -0.512942 -0.795355 0.296965 -0.528415 -0.795355 0.347794 -0.496437 -0.795355 0.376923 -0.366042 -0.850848 0.453439 -0.402249 -0.795355 0.43484 -0.422286 -0.795355 0.486859 -0.361081 -0.795355 0.53925 -0.276804 -0.795355 0.527877 -0.297921 -0.795355 0.457569 -0.258241 -0.850848 0.602551 -0.309297 -0.735709 0.497868 -0.167882 -0.850848 0.491526 -0.185631 -0.850848 0.404744 -0.152857 -0.901563 0.633618 -0.239294 -0.735709 0.641793 -0.216413 -0.735709 0.648968 -0.193839 -0.735709 0.655197 -0.171609 -0.735709 0.660534 -0.149757 -0.735709 0.665033 -0.128311 -0.735709 0.668746 -0.107293 -0.735709 0.671723 -0.0867229 -0.735709 0.674014 -0.066614 -0.735709 0.675667 -0.046978 -0.735709 0.676727 -0.0278224 -0.735709 0.677236 -0.0091523 -0.735709 0.677237 0.00915217 -0.735708 0.676727 0.0278226 -0.735708 0.675667 0.0469781 -0.735708 0.674014 0.066614 -0.735709 0.671723 0.0867228 -0.735709 0.668746 0.107293 -0.735709 0.665033 0.128311 -0.735709 0.648968 0.193839 -0.735709 0.491527 0.185632 -0.850848 0.558792 0.234866 -0.795355 0.567053 0.214155 -0.795355 0.624388 0.262437 -0.735709 0.54954 0.255766 -0.795355 0.527877 0.297921 -0.795355 0.501718 0.340133 -0.795355 0.470773 0.381816 -0.795355 0.376923 0.366042 -0.850848 0.414969 0.441828 -0.795355 0.43484 0.422286 -0.795355 0.393828 0.460772 -0.795355 0.322958 0.512942 -0.795355 0.296965 0.528415 -0.795355 0.269875 0.542751 -0.795355 0.184364 0.492003 -0.850848 0.182777 0.577931 -0.795355 0.212693 0.567603 -0.795355 0.158432 0.500955 -0.850848 0.120818 0.593981 -0.795355 0.0890127 0.599573 -0.795355 0.0568278 0.603474 -0.795355 0.0243986 0.605653 -0.795355 -0.00813573 0.60609 -0.795355 -0.0406349 0.604781 -0.795355 -0.0909901 0.517473 -0.850848 -0.136537 0.590566 -0.795355 -0.104971 0.596986 -0.795355 -0.118352 0.511908 -0.850848 -0.197835 0.57295 -0.795355 -0.227337 0.561897 -0.795355 -0.245787 0.464377 -0.850848 -0.283553 0.535732 -0.795355 -0.335523 0.504812 -0.795355 -0.331801 0.407388 -0.850848 -0.404557 0.451381 -0.795355 -0.382785 0.469986 -0.795355 -0.472002 0.230806 -0.850848 -0.554293 0.245296 -0.795355 -0.544528 0.266271 -0.795355 -0.61936 0.27409 -0.735709 -0.657974 0.160634 -0.735709 -0.670323 0.0969513 -0.735709 -0.596914 0.105377 -0.795355 -0.662885 0.138982 -0.735709 -0.602254 0.0685615 -0.795355 -0.604014 0.0507758 -0.795355 -0.677048 0.0184266 -0.735708 -0.676268 0.0373398 -0.735708 -0.58277 -0 -0.812637 -0.605223 -0.033417 -0.795355 -0.604014 -0.0507759 -0.795355 -0.199557 -0.0167756 -0.979743 -0.198976 -0.0226517 -0.979743 -0.323016 -0.0367727 -0.945679 -0.596914 -0.105377 -0.795355 -0.593245 -0.124381 -0.795355 -0.563043 -0.224484 -0.795355 -0.462618 -0.249083 -0.850848 -0.521771 -0.30849 -0.795355 -0.440942 -0.285705 -0.850848 -0.49444 -0.350629 -0.795355 -0.317126 -0.294303 -0.901563 -0.368449 -0.37457 -0.850848 -0.385121 -0.357405 -0.850848 -0.444298 -0.412323 -0.795355 -0.27322 -0.335461 -0.901563 -0.331801 -0.407388 -0.850848 -0.382785 -0.469986 -0.795355 -0.290835 -0.437575 -0.850848 -0.2688 -0.451447 -0.850848 -0.182681 -0.392187 -0.901563 -0.221851 -0.476277 -0.850848 -0.255939 -0.54946 -0.795355 -0.145218 -0.504945 -0.850848 -0.118352 -0.511908 -0.850848 -0.0909899 -0.517473 -0.850848 -0.0632419 -0.521592 -0.850848 -0.0352229 -0.52423 -0.850848 0.017415 -0.432296 -0.901563 0.0492588 -0.523098 -0.850848 0.021149 -0.524986 -0.850848 0.0405619 -0.430741 -0.901563 0.0771571 -0.519716 -0.850848 0.0635345 -0.427956 -0.901563 0.0890127 -0.599573 -0.795355 0.131854 -0.508598 -0.850848 0.158433 -0.500956 -0.850848 0.184364 -0.492004 -0.850848 0.192628 -0.387399 -0.901563 0.23393 -0.470462 -0.850848 0.269875 -0.542751 -0.795355 0.279943 -0.444623 -0.850848 0.265115 -0.341903 -0.901563 0.341374 -0.399401 -0.850848 0.321958 -0.415211 -0.850848 0.371429 -0.479011 -0.795355 0.414969 -0.441828 -0.795355 0.336023 -0.272529 -0.901563 0.422014 -0.312989 -0.850848 0.408071 -0.330962 -0.850848 0.470773 -0.381816 -0.795355 0.358111 -0.242777 -0.901563 0.446735 -0.276559 -0.850848 0.434894 -0.294831 -0.850848 0.501718 -0.340133 -0.795355 0.515379 -0.319054 -0.795355 0.54954 -0.255766 -0.795355 0.558792 -0.234866 -0.795355 0.567053 -0.214155 -0.795355 0.574369 -0.193678 -0.795355 0.58079 -0.173475 -0.795355 0.586365 -0.153581 -0.795355 0.591142 -0.134025 -0.795355 0.601155 -0.0776122 -0.795355 0.603205 -0.0596158 -0.795355 0.604684 -0.0420427 -0.795355 0.605633 -0.0248995 -0.795355 0.606089 -0.00819079 -0.795355 0.606089 0.00819068 -0.795355 0.605632 0.0248996 -0.795355 0.604684 0.0420427 -0.795355 0.603205 0.0596158 -0.795355 0.601155 0.077612 -0.795355 0.59849 0.0960216 -0.795355 0.595168 0.114831 -0.795355 0.418529 0.109621 -0.901563 0.503435 0.15037 -0.850848 0.508267 0.133125 -0.850848 0.586365 0.153581 -0.795355 0.58079 0.173475 -0.795355 0.574369 0.193678 -0.795355 0.3849 0.197574 -0.901563 0.457569 0.258241 -0.850848 0.467427 0.239936 -0.850848 0.53925 0.276804 -0.795355 0.367862 0.227731 -0.901563 0.434894 0.294831 -0.850848 0.446735 0.276559 -0.850848 0.515379 0.319054 -0.795355 0.347505 0.257729 -0.901563 0.408071 0.330962 -0.850848 0.422014 0.312989 -0.850848 0.486859 0.361081 -0.795355 0.453439 0.402249 -0.795355 0.359699 0.382981 -0.850848 0.265115 0.341903 -0.901563 0.301471 0.430316 -0.850848 0.321958 0.415211 -0.850848 0.371429 0.479011 -0.795355 0.279943 0.444623 -0.850848 0.257412 0.458035 -0.850848 0.172558 0.396746 -0.901563 0.209557 0.481812 -0.850848 0.241756 0.555846 -0.795355 0.131853 0.508598 -0.850848 0.104726 0.514869 -0.850848 0.0771571 0.519716 -0.850848 0.049259 0.523098 -0.850848 0.0211489 0.524986 -0.850848 -0.0290039 0.431674 -0.901563 -0.0632418 0.521592 -0.850848 -0.0352227 0.52423 -0.850848 -0.0520761 0.429501 -0.901563 -0.0729593 0.601737 -0.795355 -0.145218 0.504945 -0.850848 -0.171485 0.496639 -0.850848 -0.182681 0.392187 -0.901563 -0.221851 0.476277 -0.850848 -0.255939 0.54946 -0.795355 -0.2688 0.451447 -0.850848 -0.256788 0.3482 -0.901563 -0.311847 0.422858 -0.850848 -0.359764 0.487832 -0.795355 -0.303397 0.308437 -0.901563 -0.385122 0.357405 -0.850848 -0.368449 0.37457 -0.850848 -0.425063 0.432125 -0.795355 -0.462263 0.392076 -0.795355 -0.415176 0.322003 -0.850848 -0.49444 0.350629 -0.795355 -0.372424 0.220191 -0.901563 -0.462618 0.249083 -0.850848 -0.452276 0.267402 -0.850848 -0.407438 0.145527 -0.901563 -0.58885 0.143759 -0.795355 -0.593246 0.124381 -0.795355 -0.599902 0.0867661 -0.795355 -0.517411 0.0913422 -0.850848 -0.52204 0.0594298 -0.850848 -0.523565 0.044013 -0.850848 -0.60592 0.0164907 -0.795355 -0.605223 0.033417 -0.795355 -0.432487 -0.0117705 -0.901563 -0.524613 -0.0289662 -0.850848 -0.523565 -0.044013 -0.850848 -0.52204 -0.0594299 -0.850848 -0.520001 -0.0752096 -0.850848 -0.306159 -0.109352 -0.945679 -0.401883 -0.16023 -0.901563 -0.407438 -0.145527 -0.901563 -0.494797 -0.176729 -0.850848 -0.488051 -0.194585 -0.850848 -0.395637 -0.175085 -0.901563 -0.472002 -0.230806 -0.850848 -0.363092 -0.235262 -0.901563 -0.372424 -0.22019 -0.901563 -0.279849 -0.165457 -0.945679 -0.452276 -0.267402 -0.850848 -0.341875 -0.265152 -0.901563 -0.352916 -0.250268 -0.901563 -0.26519 -0.188058 -0.945679 -0.428585 -0.303928 -0.850848 -0.400694 -0.339855 -0.850848 -0.350673 -0.391261 -0.850848 -0.303397 -0.308437 -0.901563 -0.256789 -0.3482 -0.901563 -0.239486 -0.360319 -0.901563 -0.202391 -0.382389 -0.901563 -0.152082 -0.287337 -0.945679 -0.245787 -0.464378 -0.850848 -0.162266 -0.401065 -0.901563 -0.141208 -0.408954 -0.901563 -0.119579 -0.415794 -0.901563 -0.0974562 -0.421528 -0.901563 -0.0749251 -0.42611 -0.901563 -0.0058071 -0.432608 -0.901563 -0.0290041 -0.431674 -0.901563 -0.0217944 -0.324371 -0.945679 -0.00436361 -0.325073 -0.945679 -0.00705222 -0.525364 -0.850848 0.0862361 -0.423965 -0.901563 0.108574 -0.418802 -0.901563 0.13046 -0.412509 -0.901563 0.172558 -0.396746 -0.901563 0.129665 -0.298125 -0.945679 0.209557 -0.481813 -0.850848 0.211965 -0.377166 -0.901563 0.248245 -0.354342 -0.901563 0.186538 -0.266262 -0.945679 0.301471 -0.430317 -0.850848 0.310375 -0.301415 -0.901563 0.296192 -0.315363 -0.901563 0.222566 -0.236972 -0.945679 0.359699 -0.382981 -0.850848 0.393045 -0.348673 -0.850848 0.289224 -0.148462 -0.945679 0.392245 -0.182558 -0.901563 0.3849 -0.197574 -0.901563 0.467427 -0.239936 -0.850848 0.476347 -0.221701 -0.850848 0.484366 -0.203584 -0.850848 0.503434 -0.15037 -0.850848 0.508267 -0.133125 -0.850848 0.512407 -0.116174 -0.850848 0.429086 -0.0553972 -0.901563 0.522865 -0.0516756 -0.850848 0.521087 -0.067275 -0.850848 0.518777 -0.0832325 -0.850848 0.524146 -0.036443 -0.850848 0.524968 -0.0215831 -0.850848 0.525364 -0.00709986 -0.850848 0.525364 0.00709976 -0.850848 0.524968 0.0215833 -0.850848 0.524146 0.0364431 -0.850848 0.522864 0.0516756 -0.850848 0.521087 0.0672749 -0.850848 0.518777 0.0832325 -0.850848 0.515897 0.0995369 -0.850848 0.512407 0.116174 -0.850848 0.497869 0.167882 -0.850848 0.299705 0.125969 -0.945679 0.392245 0.182558 -0.901564 0.398849 0.16764 -0.901563 0.484367 0.203584 -0.850848 0.476347 0.221701 -0.850848 0.310375 0.301415 -0.901563 0.323651 0.287113 -0.901563 0.243199 0.215744 -0.945679 0.393045 0.348673 -0.850848 0.281102 0.328885 -0.901563 0.211227 0.247132 -0.945679 0.341374 0.399401 -0.850848 0.248245 0.354342 -0.901563 0.192628 0.387399 -0.901563 0.211965 0.377167 -0.901563 0.159276 0.283412 -0.945679 0.144746 0.291101 -0.945679 0.23393 0.470462 -0.850848 0.151813 0.405137 -0.901563 0.13046 0.412509 -0.901563 0.108574 0.418802 -0.901563 0.0862361 0.423965 -0.901563 0.0174149 0.432296 -0.901563 0.040562 0.430741 -0.901563 0.0304793 0.32367 -0.945679 -0.00580703 0.432608 -0.901563 0.0130861 0.324839 -0.945679 -0.00436356 0.325073 -0.945679 -0.00705213 0.525364 -0.850848 -0.0749252 0.42611 -0.901563 -0.0974562 0.421528 -0.901563 -0.119579 0.415794 -0.901563 -0.162266 0.401065 -0.901563 -0.121931 0.301371 -0.945679 -0.197058 0.487058 -0.850848 -0.202391 0.382389 -0.901563 -0.290835 0.437576 -0.850848 -0.221342 0.371741 -0.901563 -0.27322 0.335461 -0.901563 -0.350674 0.391261 -0.850848 -0.341875 0.265152 -0.901563 -0.329949 0.279852 -0.901563 -0.247933 0.210288 -0.945679 -0.400694 0.339855 -0.850848 -0.363092 0.235262 -0.901563 -0.352916 0.250268 -0.901563 -0.26519 0.188058 -0.945679 -0.428585 0.303928 -0.850848 -0.440942 0.285705 -0.850848 -0.297292 0.131563 -0.945679 -0.401883 0.16023 -0.901563 -0.395637 0.175085 -0.901563 -0.480467 0.212625 -0.850848 -0.488051 0.194585 -0.850848 -0.510421 0.124611 -0.850848 -0.514231 0.107815 -0.850848 -0.520001 0.0752096 -0.850848 -0.426059 0.0752152 -0.901563 -0.524612 0.0289662 -0.850848 -0.525217 0.0142943 -0.850848 -0.374395 -2.49655e-17 -0.927269 -0.431989 -0.023852 -0.901563 -0.431126 -0.0362422 -0.901563 -0.42987 -0.0489372 -0.901563 -0.428191 -0.0619308 -0.901563 -0.198199 -0.0286662 -0.979743 -0.0565528 -0.00643807 -0.998379 -0.0563315 -0.00814742 -0.998379 -0.197211 -0.0348151 -0.979743 -0.416613 -0.116692 -0.901563 -0.412336 -0.131005 -0.901563 -0.179905 -0.0879724 -0.979742 -0.286248 -0.154122 -0.945679 -0.292054 -0.142813 -0.945679 -0.388667 -0.190056 -0.901563 -0.38094 -0.205106 -0.901563 -0.152725 -0.129536 -0.979743 -0.238297 -0.221147 -0.945679 -0.247932 -0.210288 -0.945679 -0.329949 -0.279852 -0.901563 -0.205304 -0.252074 -0.945679 -0.216982 -0.242096 -0.945679 -0.13366 -0.14913 -0.979743 -0.28876 -0.322182 -0.901563 -0.192957 -0.261646 -0.945679 -0.166322 -0.279336 -0.945679 -0.102453 -0.172069 -0.979743 -0.221342 -0.371741 -0.901563 -0.137272 -0.2947 -0.945679 -0.121931 -0.301371 -0.945679 -0.106108 -0.307299 -0.945679 -0.0563007 -0.32019 -0.945679 -0.0732312 -0.316747 -0.945679 -0.04511 -0.195115 -0.979743 -0.0391314 -0.322739 -0.945679 -0.0346809 -0.197235 -0.979743 -0.0241047 -0.198805 -0.979743 -0.0520761 -0.429501 -0.901563 0.0130861 -0.324839 -0.945679 0.0304793 -0.32367 -0.945679 0.0477415 -0.321578 -0.945679 0.0648001 -0.318579 -0.945679 0.114076 -0.304431 -0.945679 0.0980313 -0.30997 -0.945679 0.0603867 -0.19094 -0.979743 0.0702703 -0.187527 -0.979743 0.151813 -0.405137 -0.901563 0.144746 -0.291102 -0.945679 0.159276 -0.283413 -0.945679 0.230517 -0.366122 -0.901563 0.199214 -0.256915 -0.945679 0.281102 -0.328885 -0.901563 0.14981 -0.132898 -0.979742 0.252496 -0.204785 -0.945679 0.243199 -0.215744 -0.945679 0.323651 -0.287113 -0.901563 0.347505 -0.257729 -0.901563 0.170274 -0.105411 -0.979743 0.283124 -0.159788 -0.945679 0.276421 -0.171123 -0.945679 0.367862 -0.227731 -0.901563 0.376782 -0.212647 -0.901563 0.398849 -0.16764 -0.901563 0.189763 -0.0639884 -0.979743 0.311504 -0.0930423 -0.945679 0.30806 -0.103878 -0.945679 0.409967 -0.138241 -0.901563 0.41455 -0.123821 -0.901563 0.418529 -0.109621 -0.901563 0.421938 -0.0956626 -0.901563 0.424812 -0.081963 -0.901563 0.427184 -0.0685373 -0.901563 0.430549 -0.0425519 -0.901563 0.431605 -0.0300088 -0.901563 0.432282 -0.0177725 -0.901563 0.432607 -0.00584634 -0.901563 0.432607 0.00584626 -0.901563 0.432282 0.0177726 -0.901563 0.323526 0.0319747 -0.945679 0.429086 0.0553971 -0.901563 0.430549 0.0425519 -0.901563 0.431605 0.0300088 -0.901563 0.427184 0.0685373 -0.901563 0.424812 0.081963 -0.901563 0.421938 0.0956625 -0.901563 0.191884 0.0573135 -0.979743 0.30806 0.103878 -0.945679 0.311504 0.0930424 -0.945679 0.41455 0.123821 -0.901563 0.409967 0.138241 -0.901563 0.404744 0.152857 -0.901563 0.289224 0.148462 -0.945679 0.376782 0.212647 -0.901563 0.276421 0.171123 -0.945679 0.358111 0.242776 -0.901563 0.261124 0.193664 -0.945679 0.336023 0.272529 -0.901563 0.233224 0.226491 -0.945679 0.296192 0.315363 -0.901563 0.199214 0.256915 -0.945679 0.106701 0.169469 -0.979743 0.173217 0.275113 -0.945679 0.230517 0.366122 -0.901563 0.129665 0.298125 -0.945679 0.114076 0.30443 -0.945679 0.0980312 0.30997 -0.945679 0.0477415 0.321577 -0.945679 0.0648 0.318579 -0.945679 0.0399165 0.196243 -0.979743 0.0294085 0.19809 -0.979743 0.0635345 0.427956 -0.901563 -0.0217943 0.324371 -0.945679 -0.0391313 0.322739 -0.945679 -0.0563008 0.32019 -0.945679 -0.0732312 0.316747 -0.945679 -0.106108 0.307299 -0.945679 -0.0653617 0.189295 -0.979743 -0.141208 0.408954 -0.901563 -0.137272 0.2947 -0.945679 -0.152082 0.287337 -0.945679 -0.192958 0.261647 -0.945679 -0.179956 0.270753 -0.945679 -0.110852 0.166782 -0.979743 -0.239486 0.360319 -0.901563 -0.133659 0.149129 -0.979743 -0.227981 0.231768 -0.945679 -0.216982 0.242096 -0.945679 -0.28876 0.322182 -0.901563 -0.317126 0.294303 -0.901563 -0.279849 0.165457 -0.945679 -0.38094 0.205106 -0.901563 -0.388667 0.190056 -0.901563 -0.315826 0.0771042 -0.945679 -0.313054 0.0876856 -0.945679 -0.420303 0.102611 -0.901563 -0.306159 0.109352 -0.945679 -0.42344 0.0887795 -0.901563 -0.428191 0.0619309 -0.901563 -0.42987 0.0489371 -0.901563 -0.431126 0.0362422 -0.901563 -0.323016 0.0367726 -0.945679 -0.323959 0.0272333 -0.945679 -0.432487 0.0117706 -0.901563 -0.431989 0.023852 -0.901563 0.536534 2.7244e-17 -0.843879 0.463238 0.0126074 -0.886144 0.470988 6.72016e-17 -0.882139 -0.324608 -0.017923 -0.945679 -0.32396 -0.0272334 -0.945679 -0.321754 -0.0465365 -0.945679 -0.320152 -0.0565186 -0.945679 -0.313054 -0.0876856 -0.945679 -0.30984 -0.0984407 -0.945679 -0.0528704 -0.0210793 -0.998379 -0.183131 -0.0810423 -0.979742 -0.186022 -0.0741664 -0.979742 -0.301985 -0.120401 -0.945679 -0.297292 -0.131563 -0.945679 -0.172386 -0.101921 -0.979743 -0.272836 -0.176782 -0.945679 -0.163356 -0.115843 -0.979743 -0.256893 -0.199242 -0.945679 -0.140435 -0.142768 -0.979743 -0.0399139 -0.040577 -0.998379 -0.22798 -0.231768 -0.945679 -0.126467 -0.155277 -0.979743 -0.0315061 -0.0474024 -0.998379 -0.110852 -0.166783 -0.979743 -0.179956 -0.270753 -0.945679 -0.0936819 -0.176998 -0.979743 -0.0845586 -0.181534 -0.979743 -0.0751089 -0.185643 -0.979743 -0.05535 -0.19246 -0.979743 -0.0157315 -0.0547009 -0.998379 -0.0898547 -0.312438 -0.945679 -0.0134253 -0.199811 -0.979743 -0.00268796 -0.200243 -0.979743 0.00806099 -0.200099 -0.979743 0.0187751 -0.199379 -0.979743 0.0294085 -0.19809 -0.979743 0.0502561 -0.193852 -0.979743 0.0142838 -0.0550967 -0.998379 0.0815854 -0.314699 -0.945679 0.0798727 -0.183643 -0.979743 0.0891625 -0.179317 -0.979743 0.0303261 -0.0481658 -0.998379 0.114906 -0.164015 -0.979743 0.1067 -0.169468 -0.979743 0.173217 -0.275114 -0.945679 0.0369809 -0.043267 -0.998379 0.1371 -0.145974 -0.979742 0.130115 -0.152233 -0.979742 0.211228 -0.247132 -0.945679 0.233224 -0.226491 -0.945679 0.0457166 -0.0339059 -0.998379 0.16576 -0.112375 -0.979743 0.160851 -0.119296 -0.979743 0.261124 -0.193664 -0.945679 0.269093 -0.182428 -0.945679 0.0516025 -0.0240167 -0.998379 0.184617 -0.0775964 -0.979743 0.18156 -0.0845015 -0.979743 0.294743 -0.137179 -0.945679 0.299705 -0.125969 -0.945679 0.304135 -0.114861 -0.945679 0.314494 -0.0823722 -0.945679 0.317055 -0.0718833 -0.945679 0.319215 -0.0615891 -0.945679 0.320997 -0.0515007 -0.945679 0.322426 -0.0416269 -0.945679 0.323526 -0.0319747 -0.945679 0.324319 -0.0225494 -0.945679 0.324828 -0.0133547 -0.945679 0.325073 -0.00439309 -0.945679 0.325073 0.00439303 -0.945679 0.324828 0.0133548 -0.945679 0.324319 0.0225494 -0.945679 0.0558874 0.0107829 -0.998379 -0.0973595 -0.0187845 -0.995072 0.0555093 0.0125852 -0.998379 0.322426 0.0416268 -0.945679 0.320997 0.0515007 -0.945679 0.319215 0.0615892 -0.945679 0.317056 0.0718833 -0.945679 0.314494 0.0823723 -0.945679 0.304136 0.114861 -0.945679 0.184617 0.0775962 -0.979743 0.294743 0.137179 -0.945679 0.0495682 0.0279751 -0.998379 0.170274 0.105411 -0.979742 0.174403 0.0984286 -0.979743 0.283124 0.159788 -0.945679 0.0471118 0.0319389 -0.998379 0.160851 0.119296 -0.979742 0.165761 0.112375 -0.979742 0.269093 0.182428 -0.945679 0.0442061 0.035853 -0.998379 0.14981 0.132898 -0.979742 0.155537 0.126147 -0.979742 0.252496 0.204785 -0.945679 0.038966 0.0414881 -0.998379 0.130115 0.152232 -0.979743 0.1371 0.145974 -0.979743 0.222566 0.236972 -0.945679 0.114906 0.164016 -0.979743 0.0326583 0.046616 -0.998379 0.186538 0.266261 -0.945679 0.098113 0.174581 -0.979743 0.0891627 0.179317 -0.979743 0.0798728 0.183644 -0.979743 0.0603868 0.19094 -0.979743 0.0171629 0.0542683 -0.998379 0.0502561 0.193853 -0.979743 0.0142836 0.0550962 -0.998379 0.0815852 0.314699 -0.945679 0.0187751 0.199379 -0.979743 0.00806094 0.200099 -0.979743 -0.00268793 0.200243 -0.979743 -0.0134252 0.199811 -0.979743 -0.0241047 0.198805 -0.979743 -0.04511 0.195115 -0.979743 -0.0128211 0.0554553 -0.998379 -0.05535 0.19246 -0.979743 -0.0157315 0.0547009 -0.998379 -0.0898547 0.312438 -0.945679 -0.0751089 0.185643 -0.979743 -0.0845587 0.181534 -0.979743 -0.102453 0.172069 -0.979743 -0.0291192 0.0489054 -0.998379 -0.166322 0.279336 -0.945679 -0.118861 0.161173 -0.979743 -0.205305 0.252075 -0.945679 -0.0417201 0.0387176 -0.998379 -0.152725 0.129536 -0.979743 -0.146789 0.136225 -0.979743 -0.238297 0.221147 -0.945679 -0.256894 0.199242 -0.945679 -0.163355 0.115842 -0.979743 -0.272836 0.176782 -0.945679 -0.0501152 0.0269831 -0.998379 -0.179905 0.0879723 -0.979742 -0.176328 0.0949386 -0.979742 -0.286248 0.154122 -0.945679 -0.292054 0.142813 -0.945679 -0.0528704 0.0210793 -0.998379 -0.188593 0.0673606 -0.979743 -0.186021 0.0741663 -0.979743 -0.301985 0.120401 -0.945679 -0.19086 0.060639 -0.979743 -0.320152 0.0565186 -0.945679 -0.318184 0.0667111 -0.945679 -0.321754 0.0465365 -0.945679 -0.198976 0.0226517 -0.979743 -0.199557 0.0167756 -0.979743 -0.324982 0.00884471 -0.945679 -0.324608 0.017923 -0.945679 -0.199956 -0.0110405 -0.979743 0.362771 0.00987314 -0.931826 0.392682 -3.68525e-17 -0.919674 -0.192839 -0.0540138 -0.979743 -0.19086 -0.0606391 -0.979742 -0.188593 -0.0673607 -0.979742 -0.0501152 -0.0269831 -0.998379 0.0873043 0.0470064 -0.995072 -0.0489949 -0.0289675 -0.998379 -0.176327 -0.0949383 -0.979743 -0.0477671 -0.0309503 -0.998379 0.0832138 0.0539176 -0.995072 -0.0464284 -0.0329244 -0.998379 -0.168066 -0.108897 -0.979743 -0.0449759 -0.0348825 -0.998379 0.0783512 0.0607678 -0.995072 -0.043407 -0.0368164 -0.998379 -0.158245 -0.122732 -0.979743 -0.14679 -0.136226 -0.979743 -0.0379883 -0.0423852 -0.998379 -0.0337823 -0.045808 -0.998379 0.0588511 0.0798009 -0.995072 -0.118861 -0.161173 -0.979743 -0.029119 -0.048905 -0.998379 -0.026626 -0.0503058 -0.998379 -0.0213472 -0.0527628 -0.998379 0.0371884 0.0919166 -0.995072 -0.0185769 -0.0538007 -0.998379 0.0323623 0.0937247 -0.995072 -0.0653617 -0.189295 -0.979743 -0.0128211 -0.0554553 -0.998379 -0.00985698 -0.0560581 -0.998379 -0.00685102 -0.0565043 -0.998379 -0.00381571 -0.05679 -0.998379 -0.00076397 -0.056913 -0.998379 0.00229109 -0.056872 -0.998379 0.00835846 -0.056301 -0.998379 -0.014561 0.0980801 -0.995072 0.011345 -0.055776 -0.998379 -0.0197638 0.0971654 -0.995072 0.0399165 -0.196243 -0.979743 0.0171631 -0.0542688 -0.998379 0.0199722 -0.053299 -0.998379 0.0227014 -0.052195 -0.998379 0.0278854 -0.0496188 -0.998379 -0.0485785 0.0864399 -0.995072 0.0981128 -0.17458 -0.979743 0.0326583 -0.046616 -0.998379 0.122715 -0.158258 -0.979743 0.038966 -0.0414881 -0.998379 0.143665 -0.139517 -0.979742 0.0425784 -0.0377716 -0.998379 0.155537 -0.126147 -0.979743 0.0483947 -0.0299595 -0.998379 0.174403 -0.0984288 -0.979743 0.17816 -0.0914519 -0.979743 0.187346 -0.0707537 -0.979743 -0.457558 0.0734105 -0.886144 -0.358322 0.0574891 -0.931826 -0.455018 0.0877909 -0.886144 0.191885 -0.0573136 -0.979743 0.193727 -0.0507409 -0.979743 0.195305 -0.0442798 -0.979743 0.196635 -0.0379386 -0.979743 0.197733 -0.0317242 -0.979743 0.198613 -0.0256419 -0.979743 0.19929 -0.0196962 -0.979743 0.199779 -0.0138903 -0.979743 0.200092 -0.00822644 -0.979743 0.200243 -0.00270612 -0.979743 0.200243 0.00270608 -0.979743 0.200092 0.00822648 -0.979743 0.199779 0.0138903 -0.979743 0.19929 0.0196962 -0.979743 0.198613 0.0256419 -0.979743 0.197733 0.0317242 -0.979743 0.196635 0.0379386 -0.979743 0.195305 0.0442798 -0.979743 0.193726 0.0507408 -0.979743 -0.0939572 -0.0316825 -0.995072 0.0532469 0.0201094 -0.998379 0.0539343 0.0181867 -0.998379 0.189763 0.0639883 -0.979743 0.187346 0.0707536 -0.979743 -0.0898956 -0.0418391 -0.995072 0.0506362 0.0259922 -0.998379 0.0516025 0.0240167 -0.998379 0.18156 0.0845013 -0.979743 0.17816 0.0914518 -0.979743 0.0408319 0.0396531 -0.998379 -0.0711322 -0.0690786 -0.995072 0.143665 0.139517 -0.979743 0.0369809 0.043267 -0.998379 0.122715 0.158258 -0.979743 0.0303261 0.0481658 -0.998379 0.0278854 0.0496188 -0.998379 0.0227012 0.0521946 -0.998379 -0.0395471 -0.0909267 -0.995072 0.0199721 0.0532985 -0.998379 -0.0347928 -0.0928499 -0.995072 0.0702705 0.187528 -0.979743 0.0113449 0.0557755 -0.998379 0.00835839 0.0563006 -0.998379 0.0053362 0.0566669 -0.998379 0.00229105 0.0568715 -0.998379 -0.000763954 0.0569125 -0.998379 -0.00685101 0.0565043 -0.998379 0.0119349 -0.0984337 -0.995072 -0.00985699 0.0560581 -0.998379 0.0171715 -0.0976564 -0.995072 -0.034681 0.197235 -0.979743 -0.018577 0.0538011 -0.998379 -0.0213474 0.0527632 -0.998379 -0.0266262 0.0503062 -0.998379 0.0463846 -0.0876368 -0.995072 -0.0936819 0.176998 -0.979743 -0.0315063 0.0474028 -0.998379 -0.0359442 0.0441326 -0.998379 0.0626172 -0.0768818 -0.995072 -0.0379886 0.0423855 -0.998379 -0.126466 0.155276 -0.979743 -0.140435 0.142768 -0.979743 -0.0449759 0.0348825 -0.998379 0.0783516 -0.060768 -0.995072 -0.0464284 0.0329244 -0.998379 -0.158245 0.122732 -0.979743 0.0832141 -0.0539179 -0.995072 -0.0489949 0.0289675 -0.998379 -0.0477671 0.0309503 -0.998379 -0.168066 0.108897 -0.979742 -0.172386 0.101921 -0.979742 -0.18313 0.0810422 -0.979743 -0.198199 0.0286663 -0.979743 -0.0565524 0.00643801 -0.998379 -0.0567176 0.00476791 -0.998379 -0.200187 0.0054483 -0.979743 -0.199957 0.0110405 -0.979743 0.0672886 -3.46053e-17 -0.997734 0.0991184 0.0026976 -0.995072 -0.0568315 -0.00313792 -0.998379 -0.056718 -0.00476795 -0.998379 0.239952 0.0273165 -0.9704 0.361629 0.0304 -0.931826 0.357379 0.0630905 -0.931826 -0.0552937 -0.0134991 -0.998379 -0.0536012 -0.019145 -0.998379 0.0921045 0.0367218 -0.995072 -0.0520488 -0.0230335 -0.998379 -0.0511318 -0.0250032 -0.998379 0.0726794 0.0674489 -0.995072 0.177018 0.164279 -0.9704 0.0695329 0.0706881 -0.995072 -0.0417201 -0.0387176 -0.998379 0.0626169 0.0768815 -0.995072 0.15251 0.187253 -0.9704 -0.0359439 -0.0441322 -0.998379 0.0548858 0.0825784 -0.995072 0.0507274 0.0851961 -0.995072 0.0418672 0.089882 -0.995072 0.101972 0.218917 -0.9704 -0.024033 -0.0515949 -0.998379 0.0274052 0.0952921 -0.995072 0.0223351 0.0966063 -0.995072 0.0171714 0.0976564 -0.995072 0.0119349 0.0984337 -0.995072 0.00133089 0.0991461 -0.995072 0.00324149 0.241479 -0.970401 -0.00399122 0.0990747 -0.995072 -0.00972098 0.241305 -0.970401 -0.00929607 0.0987183 -0.995072 -0.0226414 0.240437 -0.970401 0.00533623 -0.0566674 -0.998379 -0.0248832 0.095982 -0.995072 -0.0298992 0.0945398 -0.995072 -0.0347929 0.0928503 -0.995072 -0.044147 0.088785 -0.995072 -0.107524 0.216244 -0.9704 0.0253415 -0.0509649 -0.998379 -0.0528305 0.0839087 -0.995072 -0.0607596 0.0783582 -0.995072 -0.147986 0.190849 -0.9704 -0.0644237 0.0753745 -0.995072 0.0348776 -0.0449797 -0.998379 -0.0711322 0.0690786 -0.995072 -0.17325 0.168248 -0.9704 -0.0741746 0.0658009 -0.995072 0.0408319 -0.0396531 -0.998379 -0.0770103 0.0624585 -0.995072 -0.187567 0.152124 -0.9704 -0.0796415 0.0590666 -0.995072 0.0442061 -0.035853 -0.998379 -0.0820722 0.0556398 -0.995072 -0.199895 0.135517 -0.9704 -0.084307 0.0521917 -0.995072 0.0471118 -0.0319389 -0.998379 -0.0863514 0.0487347 -0.995072 -0.210318 0.118698 -0.9704 -0.0882119 0.0452802 -0.995072 0.0495682 -0.0279751 -0.998379 0.0506362 -0.0259922 -0.998379 -0.0914086 0.03842 -0.995072 -0.222635 0.093576 -0.9704 -0.0927599 0.035032 -0.995072 0.0524712 -0.0220542 -0.998379 0.0532469 -0.0201094 -0.998379 0.0539339 -0.0181866 -0.998379 0.0545369 -0.0162895 -0.998379 0.0550603 -0.0144214 -0.998379 0.0555089 -0.0125851 -0.998379 0.0558869 -0.0107828 -0.998379 0.0561989 -0.00901654 -0.998379 0.0564491 -0.00728787 -0.998379 0.0566417 -0.005598 -0.998379 0.056781 -0.00394789 -0.998379 0.05687 -0.00233811 -0.998379 0.0569129 -0.000769131 -0.998379 0.0569129 0.000769121 -0.998379 0.05687 0.00233812 -0.998379 0.056781 0.00394789 -0.998379 0.0566421 0.00559804 -0.998379 0.0564496 0.00728792 -0.998379 0.0561994 0.00901661 -0.998379 0.0550608 0.0144215 -0.998379 0.0545373 0.0162896 -0.998379 0.0524712 0.0220542 -0.998379 -0.0843074 -0.0521919 -0.995072 -0.205339 -0.127118 -0.9704 -0.0820726 -0.0556401 -0.995072 0.0483947 0.0299595 -0.998379 0.0457166 0.0339059 -0.998379 -0.0770103 -0.0624585 -0.995072 0.0425784 0.0377717 -0.998379 -0.0678817 -0.0722753 -0.995072 -0.0607593 -0.0783578 -0.995072 -0.147986 -0.190849 -0.9704 -0.0568931 -0.0812085 -0.995072 0.0348776 0.0449797 -0.998379 -0.0528303 -0.0839083 -0.995072 -0.0441468 -0.0887846 -0.995072 -0.107524 -0.216244 -0.9704 0.0253415 0.0509649 -0.998379 -0.0298991 -0.0945393 -0.995072 -0.0248831 -0.0959816 -0.995072 -0.0197637 -0.097165 -0.995072 -0.0145609 -0.0980797 -0.995072 -0.00929604 -0.0987179 -0.995072 0.00133086 -0.0991457 -0.995072 0.00324146 -0.24148 -0.9704 0.00664716 -0.0989316 -0.995072 0.0161899 -0.240959 -0.9704 -0.00381569 0.05679 -0.998379 0.0223351 -0.0966063 -0.995072 0.0274054 -0.0952926 -0.995072 0.0323624 -0.0937251 -0.995072 0.0418674 -0.0898824 -0.995072 0.101972 -0.218917 -0.970401 -0.0240332 0.0515953 -0.998379 0.0507276 -0.0851965 -0.995072 0.054886 -0.0825788 -0.995072 -0.0337825 0.0458084 -0.998379 0.0661787 -0.0738384 -0.995072 -0.0399139 0.040577 -0.998379 0.0726797 -0.0674491 -0.995072 -0.043407 0.0368164 -0.998379 0.0890752 -0.0435573 -0.995072 0.216952 -0.106088 -0.9704 0.0906727 -0.0401261 -0.995072 -0.0511318 0.0250032 -0.998379 -0.0520488 0.0230335 -0.998379 0.341759 -0.122068 -0.931826 -0.0536012 0.019145 -0.998379 -0.0542456 0.0172346 -0.998379 0.239014 -0.0345695 -0.9704 0.359167 -0.0519477 -0.931826 0.0933771 -0.033352 -0.995072 0.0944997 -0.030024 -0.995072 -0.0563315 0.00814743 -0.998379 0.0976447 -0.0172379 -0.995072 -0.0568966 0.0015485 -0.998379 -0.0568311 0.0031379 -0.998379 0.190685 1.03781e-16 -0.981651 0.241412 0.00657025 -0.9704 0.0990043 0.00546646 -0.995072 0.0988066 0.00830608 -0.995072 0.0985187 0.0112155 -0.995072 0.098134 0.0141935 -0.995072 0.096326 0.0235165 -0.995072 0.345868 0.109887 -0.931826 0.230164 0.0731264 -0.9704 0.349456 0.0978816 -0.931826 0.0945002 0.0300241 -0.995072 0.0933775 0.0333521 -0.995072 0.331861 0.146861 -0.931826 0.220843 0.0977313 -0.9704 0.3371 0.134401 -0.931826 0.0906727 0.0401261 -0.995072 0.0890752 0.0435573 -0.995072 0.212639 0.114489 -0.9704 0.0853526 0.0504635 -0.995072 0.202676 0.131322 -0.9704 0.0808817 0.0573567 -0.995072 0.190833 0.148006 -0.9704 0.0756182 0.0641368 -0.995072 0.169355 0.172168 -0.9704 0.0661784 0.073838 -0.995072 0.143338 0.194363 -0.9704 0.13368 0.201129 -0.9704 0.169766 0.320748 -0.931826 0.112974 0.213448 -0.9704 0.185662 0.311817 -0.931826 0.0463843 0.0876364 -0.995072 0.0905763 0.223873 -0.9704 0.0788219 0.228277 -0.9704 0.0667484 0.232094 -0.9704 0.0543997 0.235295 -0.9704 0.0436815 0.360266 -0.931826 0.0290686 0.239745 -0.970401 0.0628473 0.357422 -0.931826 0.0243287 0.362089 -0.931826 0.0161899 0.240958 -0.970401 0.00664723 0.098932 -0.995072 -0.0354647 0.238883 -0.9704 -0.0481366 0.236655 -0.9704 -0.0606055 0.233773 -0.9704 -0.127341 0.33983 -0.931826 -0.0847414 0.226146 -0.9704 -0.10943 0.346013 -0.931826 -0.144742 0.332791 -0.931826 -0.0963212 0.221461 -0.9704 -0.0395473 0.0909271 -0.995072 -0.118318 0.210532 -0.9704 -0.208228 0.297222 -0.931826 -0.138569 0.197792 -0.9704 -0.193358 0.307104 -0.931826 -0.0568933 0.0812088 -0.995072 -0.15691 0.183582 -0.9704 -0.0678819 0.0722756 -0.995072 -0.0898952 0.0418389 -0.995072 -0.0939567 0.0316823 -0.995072 -0.0950071 0.0283775 -0.995072 -0.0959191 0.0251231 -0.995072 -0.0967004 0.0219241 -0.995072 -0.097359 0.0187844 -0.995072 -0.0979026 0.0157075 -0.995072 -0.0983384 0.012696 -0.995072 -0.0986739 0.00975211 -0.995072 -0.0989158 0.00687746 -0.995072 -0.0990709 0.00407312 -0.995072 -0.0991456 0.00133987 -0.995072 -0.0991456 -0.00133985 -0.995072 -0.0990709 -0.00407315 -0.995072 -0.0989163 -0.00687749 -0.995072 -0.0986743 -0.00975216 -0.995072 -0.0983389 -0.012696 -0.995072 -0.097903 -0.0157075 -0.995072 -0.580311 -0.195682 -0.790537 -0.516893 -0.174297 -0.838118 -0.586799 -0.17527 -0.790537 -0.0967009 -0.0219242 -0.995072 -0.0959195 -0.0251232 -0.995072 -0.0950076 -0.0283776 -0.995072 -0.433523 -0.163726 -0.886144 -0.427208 -0.17956 -0.886144 -0.334555 -0.140617 -0.931826 -0.0927603 -0.0350322 -0.995072 -0.0914091 -0.0384202 -0.995072 -0.322855 -0.165725 -0.931826 -0.214849 -0.110285 -0.9704 -0.329016 -0.15313 -0.931826 -0.0882123 -0.0452805 -0.995072 -0.0863518 -0.0487349 -0.995072 -0.291487 -0.216183 -0.931826 -0.193975 -0.143863 -0.9704 -0.300384 -0.203641 -0.931826 -0.0796419 -0.0590669 -0.995072 -0.271478 -0.240831 -0.931826 -0.18066 -0.160265 -0.9704 -0.281857 -0.228597 -0.931826 -0.0741746 -0.0658009 -0.995072 -0.17325 -0.168248 -0.9704 -0.235789 -0.275869 -0.931826 -0.15691 -0.183582 -0.9704 -0.248446 -0.264527 -0.931826 -0.0644234 -0.0753742 -0.995072 -0.138569 -0.197792 -0.9704 -0.177796 -0.316367 -0.931826 -0.118318 -0.210532 -0.9704 -0.193358 -0.307103 -0.931826 -0.0485783 -0.0864395 -0.995072 -0.0963212 -0.221461 -0.9704 -0.0847415 -0.226146 -0.9704 -0.0728223 -0.23026 -0.9704 -0.0606055 -0.233774 -0.9704 -0.0532928 -0.35897 -0.931826 -0.0354647 -0.238884 -0.9704 -0.0723349 -0.355623 -0.931826 -0.0340234 -0.361307 -0.931826 -0.0226415 -0.240438 -0.9704 -0.0146077 -0.362611 -0.931826 -0.00972096 -0.241306 -0.9704 -0.00399118 -0.0990743 -0.995072 0.0290687 -0.239746 -0.9704 0.0418228 -0.237852 -0.970401 0.0543995 -0.235294 -0.970401 0.0667482 -0.232094 -0.970401 0.136109 -0.336414 -0.931826 0.0905761 -0.223872 -0.970401 0.118446 -0.343032 -0.931826 0.0371886 -0.091917 -0.995072 0.112974 -0.213448 -0.9704 0.123552 -0.207504 -0.9704 0.215395 -0.29207 -0.931826 0.143338 -0.194363 -0.9704 0.200881 -0.302236 -0.931826 0.0588514 -0.0798012 -0.995072 0.15251 -0.187253 -0.9704 0.25449 -0.258718 -0.931826 0.169355 -0.172168 -0.9704 0.242212 -0.270247 -0.931826 0.0695332 -0.0706884 -0.995072 0.177018 -0.164279 -0.9704 0.0756185 -0.0641371 -0.995072 0.190833 -0.148006 -0.9704 0.0808821 -0.057357 -0.995072 0.202676 -0.131322 -0.9704 0.085353 -0.0504638 -0.995072 0.0873042 -0.0470065 -0.995072 0.0921041 -0.0367217 -0.995072 0.0954799 -0.0267437 -0.995072 0.22743 -0.0812322 -0.9704 0.0970446 -0.0203466 -0.995072 0.0981335 -0.0141934 -0.995072 0.0985183 -0.0112155 -0.995072 0.0988061 -0.00830604 -0.995072 0.239952 -0.0273164 -0.9704 0.240653 -0.0202302 -0.9704 0.0991179 -0.0026976 -0.995072 0.0990038 -0.00546644 -0.995072 0.299575 -1.37491e-16 -0.954073 0.241134 0.0133141 -0.9704 0.240653 0.0202302 -0.9704 0.236362 0.0495562 -0.9704 0.234611 0.0572767 -0.9704 0.232551 0.065137 -0.9704 0.22743 0.0812322 -0.9704 0.224329 0.0894395 -0.9704 0.216952 0.106088 -0.9704 0.408026 0.219689 -0.886144 0.398904 0.235847 -0.886144 0.312389 0.184696 -0.931826 0.207885 0.122909 -0.9704 0.388908 0.25199 -0.886144 0.378009 0.268062 -0.886144 0.296026 0.209925 -0.931826 0.196996 0.139698 -0.9704 0.366183 0.284005 -0.886144 0.35341 0.29975 -0.886144 0.276762 0.23474 -0.931826 0.184176 0.156212 -0.9704 0.266006 0.246862 -0.931826 0.32497 0.330368 -0.886144 0.309292 0.34509 -0.886144 0.242212 0.270246 -0.931826 0.161184 0.17984 -0.9704 0.229177 0.281385 -0.931826 0.275047 0.372958 -0.886144 0.256515 0.385939 -0.886144 0.200881 0.302236 -0.931826 0.23708 0.398173 -0.886144 0.123552 0.207504 -0.9704 0.153233 0.328967 -0.931826 0.136109 0.336414 -0.931826 0.151249 0.438032 -0.886144 0.128081 0.445358 -0.886144 0.100303 0.348768 -0.931826 0.104386 0.4515 -0.886144 0.0817464 0.353578 -0.931826 0.0802525 0.456408 -0.886144 0.0418228 0.237852 -0.970401 0.00487101 0.362872 -0.931826 -0.0146078 0.362611 -0.931826 -0.0340234 0.361307 -0.931826 -0.0532928 0.358971 -0.931826 -0.0923678 0.454111 -0.886144 -0.116294 0.44858 -0.886144 -0.091072 0.351292 -0.931826 -0.139736 0.441839 -0.886144 -0.0728223 0.23026 -0.9704 -0.161577 0.324951 -0.931826 -0.227036 0.403984 -0.886144 -0.246908 0.392154 -0.886144 -0.128674 0.204367 -0.9704 -0.222378 0.286789 -0.931826 -0.317252 0.337786 -0.886144 -0.248446 0.264527 -0.931826 -0.301089 0.352269 -0.886144 -0.165333 0.176034 -0.9704 -0.332444 0.322846 -0.886144 -0.346663 0.307527 -0.886144 -0.271478 0.240831 -0.931826 -0.18066 0.160265 -0.9704 -0.281857 0.228597 -0.931826 -0.193975 0.143863 -0.9704 -0.300383 0.203641 -0.931826 -0.291487 0.216183 -0.931826 -0.205339 0.127118 -0.9704 -0.403572 0.227766 -0.886144 -0.412268 0.211622 -0.886144 -0.322854 0.165725 -0.931826 -0.214849 0.110285 -0.9704 -0.218949 0.101903 -0.9704 -0.439117 0.148071 -0.886144 -0.510309 0.192725 -0.838118 -0.516893 0.174297 -0.838118 -0.225926 0.0853241 -0.9704 -0.228841 0.0771656 -0.9704 -0.2314 0.0691163 -0.9704 -0.233621 0.06119 -0.9704 -0.235524 0.0533985 -0.9704 -0.237129 0.0457514 -0.9704 -0.238452 0.0382572 -0.9704 -0.239514 0.0309225 -0.9704 -0.240331 0.0237523 -0.9704 -0.24092 0.0167508 -0.9704 -0.241298 0.00992054 -0.9704 -0.24148 0.0032634 -0.9704 -0.241479 -0.00326335 -0.970401 -0.241297 -0.00992056 -0.970401 -0.240919 -0.0167507 -0.970401 -0.24033 -0.0237523 -0.970401 -0.239513 -0.0309223 -0.970401 -0.238452 -0.0382571 -0.970401 -0.237128 -0.0457514 -0.9704 -0.235524 -0.0533984 -0.9704 -0.233621 -0.06119 -0.9704 -0.2314 -0.0691163 -0.9704 -0.228841 -0.0771657 -0.9704 -0.225926 -0.0853241 -0.9704 -0.222635 -0.0935759 -0.9704 -0.218949 -0.101903 -0.9704 -0.210318 -0.118698 -0.9704 -0.308563 -0.191021 -0.931826 -0.316045 -0.178368 -0.931826 -0.199896 -0.135517 -0.9704 -0.187567 -0.152124 -0.9704 -0.332444 -0.322846 -0.886144 -0.317252 -0.337786 -0.886144 -0.165333 -0.176034 -0.9704 -0.222378 -0.286789 -0.931826 -0.265896 -0.379536 -0.886144 -0.246908 -0.392154 -0.886144 -0.128674 -0.204367 -0.9704 -0.161577 -0.32495 -0.931826 -0.144742 -0.332791 -0.931826 -0.162608 -0.433944 -0.886144 -0.139736 -0.44184 -0.886144 -0.10943 -0.346013 -0.931826 -0.116294 -0.44858 -0.886144 -0.0910719 -0.351291 -0.931826 -0.0923678 -0.454111 -0.886144 -0.0481367 -0.236656 -0.9704 0.00487095 -0.362872 -0.931826 0.0243285 -0.362089 -0.931826 0.0436815 -0.360266 -0.931826 0.0628474 -0.357422 -0.931826 0.104386 -0.4515 -0.886144 0.128081 -0.445358 -0.886144 0.100303 -0.348768 -0.931826 0.151248 -0.438032 -0.886144 0.0788216 -0.228276 -0.970401 0.153234 -0.328967 -0.931826 0.169766 -0.320748 -0.931826 0.23708 -0.398173 -0.886144 0.256514 -0.385939 -0.886144 0.13368 -0.201128 -0.9704 0.292647 -0.359314 -0.886144 0.309292 -0.34509 -0.886144 0.161184 -0.17984 -0.9704 0.339675 -0.315229 -0.886144 0.353409 -0.29975 -0.886144 0.276762 -0.23474 -0.931826 0.184176 -0.156212 -0.9704 0.366183 -0.284004 -0.886144 0.378009 -0.268062 -0.886144 0.296026 -0.209925 -0.931826 0.196996 -0.139698 -0.9704 0.469559 -0.27762 -0.838118 0.480295 -0.258601 -0.838118 0.408025 -0.21969 -0.886144 0.207885 -0.122909 -0.9704 0.212639 -0.114489 -0.9704 0.416302 -0.20357 -0.886144 0.423768 -0.187533 -0.886144 0.331861 -0.146861 -0.931826 0.220843 -0.0977313 -0.9704 0.224329 -0.0894395 -0.9704 0.234611 -0.0572767 -0.9704 0.360576 -0.0410485 -0.931826 0.361629 -0.0304 -0.931826 0.241135 -0.0133141 -0.9704 0.241412 -0.00657029 -0.9704 0.678166 1.27374e-16 -0.734909 0.71292 1.00793e-16 -0.701245 0.712809 0.0193997 -0.70109 0.362353 0.0200071 -0.931826 0.667118 0.0181562 -0.744731 0.612188 0.0166613 -0.790537 0.638204 1.0194e-16 -0.769868 0.606108 0.0876635 -0.790537 0.355182 0.0744683 -0.931826 0.352551 0.0860699 -0.931826 0.506701 0.20202 -0.838118 0.576731 0.205994 -0.790537 0.568868 0.226806 -0.790537 0.341759 0.122068 -0.931826 0.480295 0.258601 -0.838118 0.550161 0.269026 -0.790536 0.539223 0.290329 -0.790536 0.326015 0.159419 -0.931826 0.319532 0.172043 -0.931826 0.304561 0.197338 -0.931826 0.286765 0.222409 -0.931826 0.399838 0.371063 -0.838118 0.382528 0.388883 -0.838118 0.25449 0.258718 -0.931826 0.34448 0.422955 -0.838118 0.323763 0.439016 -0.838118 0.215394 0.29207 -0.931826 0.216782 0.409578 -0.886144 0.230328 0.494476 -0.838118 0.204588 0.50567 -0.838118 0.173804 0.429582 -0.886144 0.178038 0.515617 -0.838118 0.118446 0.343031 -0.931826 0.0557789 0.46004 -0.886144 0.0310664 0.462367 -0.886144 0.00622 0.463368 -0.886144 -0.0219572 0.545047 -0.838118 -0.0511411 0.543086 -0.838118 -0.0434459 0.461368 -0.886144 -0.0801054 0.539575 -0.838118 -0.068052 0.458385 -0.886144 -0.108728 0.534543 -0.838118 -0.072335 0.355623 -0.931826 -0.162608 0.433944 -0.886144 -0.184828 0.424955 -0.886144 -0.242869 0.488439 -0.838118 -0.267249 0.475538 -0.838118 -0.177796 0.316368 -0.931826 -0.265896 0.379536 -0.886144 -0.334261 0.431077 -0.838118 -0.354419 0.414663 -0.838118 -0.235789 0.275869 -0.931826 -0.260343 0.252827 -0.931826 -0.423664 0.343609 -0.838118 -0.43814 0.324949 -0.838118 -0.372213 0.276054 -0.886144 -0.451512 0.306097 -0.838118 -0.463806 0.287127 -0.838118 -0.394017 0.243923 -0.886144 -0.308562 0.191021 -0.931826 -0.316045 0.178368 -0.931826 -0.329015 0.15313 -0.931826 -0.334554 0.140617 -0.931826 -0.3395 0.128217 -0.931826 -0.34388 0.115957 -0.931826 -0.347725 0.103861 -0.931826 -0.351063 0.0919503 -0.931826 -0.353922 0.0802419 -0.931826 -0.356333 0.0687506 -0.931826 -0.359918 0.0464672 -0.931826 -0.361145 0.0356926 -0.931826 -0.362031 0.0251714 -0.931826 -0.362599 0.0149076 -0.931826 -0.362872 0.00490392 -0.931826 -0.362872 -0.00490385 -0.931826 -0.362599 -0.0149077 -0.931826 -0.362031 -0.0251714 -0.931826 -0.361145 -0.0356926 -0.931826 -0.359918 -0.0464672 -0.931826 -0.358322 -0.0574892 -0.931826 -0.356333 -0.0687507 -0.931826 -0.353923 -0.0802419 -0.931826 -0.351063 -0.0919504 -0.931826 -0.347725 -0.103861 -0.931826 -0.343881 -0.115957 -0.931826 -0.3395 -0.128217 -0.931826 -0.485288 -0.249105 -0.838118 -0.475053 -0.268109 -0.838118 -0.403572 -0.227766 -0.886144 -0.463806 -0.287127 -0.838118 -0.451512 -0.306097 -0.838118 -0.383573 -0.260038 -0.886144 -0.43814 -0.324949 -0.838118 -0.423664 -0.343609 -0.838118 -0.359915 -0.291906 -0.886144 -0.346663 -0.307527 -0.886144 -0.260343 -0.252827 -0.931826 -0.301089 -0.352269 -0.886144 -0.334261 -0.431077 -0.838118 -0.312991 -0.44676 -0.838118 -0.208228 -0.297222 -0.931826 -0.227036 -0.403984 -0.886144 -0.242869 -0.488439 -0.838118 -0.217564 -0.500223 -0.838118 -0.184828 -0.424956 -0.886144 -0.191409 -0.510804 -0.838118 -0.127341 -0.339829 -0.931826 -0.068052 -0.458386 -0.886144 -0.043446 -0.461369 -0.886144 -0.0186532 -0.463034 -0.886144 0.00621993 -0.463368 -0.886144 0.0365686 -0.544262 -0.838118 0.0656584 -0.541523 -0.838118 0.0557789 -0.46004 -0.886144 0.0944669 -0.537247 -0.838118 0.0802526 -0.456408 -0.886144 0.122874 -0.531469 -0.838118 0.0817464 -0.353578 -0.931826 0.173804 -0.429582 -0.886144 0.230328 -0.494476 -0.838118 0.255179 -0.482122 -0.838118 0.216782 -0.409578 -0.886144 0.279071 -0.468697 -0.838118 0.185662 -0.311817 -0.931826 0.323763 -0.439016 -0.838118 0.34448 -0.422955 -0.838118 0.229177 -0.281386 -0.931826 0.382528 -0.388883 -0.838118 0.399838 -0.371063 -0.838118 0.266006 -0.246862 -0.931826 0.286765 -0.222409 -0.931826 0.304562 -0.197338 -0.931826 0.31239 -0.184696 -0.931826 0.319533 -0.172043 -0.931826 0.326015 -0.159419 -0.931826 0.3371 -0.134401 -0.931826 0.594942 -0.145246 -0.790536 0.599383 -0.125668 -0.790536 0.53388 -0.111935 -0.838118 0.349455 -0.0978816 -0.931826 0.539871 -0.0780835 -0.838118 0.458637 -0.0663344 -0.886144 0.537182 -0.0948325 -0.838118 0.460436 -0.0524167 -0.886144 0.461781 -0.0388192 -0.886144 0.36277 -0.00987317 -0.931826 0.362353 -0.0200071 -0.931826 0.545287 0.0148405 -0.838118 0.462705 0.025548 -0.886144 0.461781 0.0388192 -0.886144 0.456353 0.0805631 -0.886144 0.453548 0.0950919 -0.886144 0.450188 0.109906 -0.886144 0.446235 0.124989 -0.886144 0.441654 0.14032 -0.886144 0.436408 0.155874 -0.886144 0.430458 0.171623 -0.886144 0.423768 0.187533 -0.886144 0.416302 0.20357 -0.886144 0.527169 0.311681 -0.790536 0.513959 0.333015 -0.790536 0.457792 0.296622 -0.838118 0.499555 0.354256 -0.790536 0.483926 0.375324 -0.790536 0.431041 0.334307 -0.838118 0.416005 0.352842 -0.838118 0.339675 0.315229 -0.886144 0.408742 0.456051 -0.790536 0.386745 0.474848 -0.790536 0.292647 0.359314 -0.886144 0.301948 0.454296 -0.838118 0.313311 0.526202 -0.790536 0.286487 0.541274 -0.790536 0.255179 0.482122 -0.838118 0.258587 0.555144 -0.790536 0.195671 0.420073 -0.886144 0.150767 0.52424 -0.838118 0.122874 0.531469 -0.838118 0.0944668 0.537247 -0.838118 0.0410555 0.611037 -0.790536 0.0365689 0.544262 -0.838118 0.0737142 0.607962 -0.790536 0.00822 0.61236 -0.790536 0.00732169 0.54544 -0.838118 -0.0246511 0.611919 -0.790536 -0.0186533 0.463034 -0.886144 -0.136892 0.528033 -0.838118 -0.164487 0.520098 -0.838118 -0.244257 0.561596 -0.790537 -0.217564 0.500224 -0.838118 -0.214893 0.573475 -0.790537 -0.272667 0.548366 -0.790537 -0.206325 0.414944 -0.886144 -0.29064 0.461613 -0.838118 -0.375271 0.483966 -0.790537 -0.351392 0.501573 -0.790537 -0.283965 0.366213 -0.886144 -0.419262 0.446398 -0.790537 -0.439338 0.426654 -0.790537 -0.391326 0.380029 -0.838118 -0.408064 0.361997 -0.838118 -0.359915 0.291906 -0.886144 -0.383573 0.260038 -0.886144 -0.564573 0.237296 -0.790536 -0.605044 0.281599 -0.744731 -0.61523 0.258588 -0.744731 -0.420135 0.195539 -0.886144 -0.427208 0.17956 -0.886144 -0.433523 0.163726 -0.886144 -0.444026 0.132625 -0.886144 -0.448288 0.117416 -0.886144 -0.45194 0.102465 -0.886144 -0.542844 0.0536502 -0.838118 -0.461163 0.0455775 -0.886144 -0.540999 0.0698457 -0.838118 -0.459595 0.0593361 -0.886144 -0.462294 0.0321425 -0.886144 -0.463019 0.0190362 -0.886144 -0.463367 0.00626203 -0.886144 -0.463367 -0.00626195 -0.886144 -0.463019 -0.0190363 -0.886144 -0.462293 -0.0321425 -0.886144 -0.461163 -0.0455775 -0.886144 -0.459595 -0.059336 -0.886144 -0.457558 -0.0734105 -0.886144 -0.455018 -0.0877908 -0.886144 -0.45194 -0.102464 -0.886144 -0.448288 -0.117416 -0.886144 -0.444026 -0.132625 -0.886144 -0.439117 -0.148071 -0.886144 -0.564573 -0.237296 -0.790537 -0.555225 -0.258412 -0.790537 -0.494549 -0.230172 -0.838118 -0.420135 -0.195538 -0.886144 -0.412267 -0.211622 -0.886144 -0.394017 -0.243923 -0.886144 -0.372213 -0.276054 -0.886144 -0.439338 -0.426655 -0.790536 -0.391326 -0.380029 -0.838118 -0.45813 -0.406411 -0.790536 -0.373444 -0.397615 -0.838118 -0.375272 -0.483966 -0.790536 -0.397902 -0.465538 -0.790536 -0.283965 -0.366213 -0.886144 -0.29064 -0.461612 -0.838118 -0.272667 -0.548366 -0.790536 -0.300037 -0.533882 -0.790536 -0.206325 -0.414944 -0.886144 -0.164487 -0.520098 -0.838118 -0.136892 -0.528033 -0.838118 -0.108728 -0.534543 -0.838118 -0.0574157 -0.609718 -0.790536 -0.0511412 -0.543086 -0.838118 -0.0899336 -0.605776 -0.790536 -0.024651 -0.611919 -0.790536 -0.0219571 -0.545047 -0.838118 0.0082199 -0.61236 -0.790536 0.0073216 -0.54544 -0.838118 0.0410553 -0.611037 -0.790536 0.0310662 -0.462367 -0.886144 0.150767 -0.52424 -0.838118 0.178038 -0.515617 -0.838118 0.258587 -0.555144 -0.790537 0.229689 -0.56771 -0.790536 0.195671 -0.420073 -0.886144 0.338995 -0.510034 -0.790537 0.363486 -0.492879 -0.790537 0.275047 -0.372958 -0.886144 0.364074 -0.406212 -0.838118 0.324969 -0.330368 -0.886144 0.467045 -0.396132 -0.790537 0.483926 -0.375324 -0.790537 0.431041 -0.334307 -0.838118 0.499555 -0.354256 -0.790537 0.513958 -0.333015 -0.790537 0.457792 -0.296622 -0.838118 0.388908 -0.25199 -0.886144 0.398904 -0.235847 -0.886144 0.576731 -0.205994 -0.790536 0.619911 -0.247157 -0.744731 0.628479 -0.224477 -0.744731 0.430458 -0.171623 -0.886144 0.436408 -0.155874 -0.886144 0.441654 -0.14032 -0.886144 0.446235 -0.12499 -0.886144 0.450188 -0.109906 -0.886144 0.543571 -0.0456948 -0.838118 0.463238 -0.0126075 -0.886144 0.462705 -0.025548 -0.886144 0.59158 5.13502e-17 -0.806246 0.544659 0.030073 -0.838118 0.543571 0.0456948 -0.838118 0.537182 0.0948325 -0.838118 0.533881 0.111935 -0.838118 0.529925 0.129373 -0.838118 0.525273 0.147128 -0.838118 0.519881 0.165174 -0.838118 0.513705 0.183482 -0.838118 0.498826 0.22075 -0.838118 0.490038 0.239626 -0.838118 0.469559 0.27762 -0.838118 0.444962 0.315542 -0.838118 0.508952 0.431676 -0.744731 0.489172 0.453968 -0.744731 0.448894 0.416589 -0.790536 0.429461 0.436596 -0.790536 0.364073 0.406212 -0.838118 0.363486 0.492879 -0.790536 0.369412 0.555798 -0.744731 0.341423 0.573416 -0.744731 0.279071 0.468697 -0.838118 0.229689 0.567711 -0.790536 0.199881 0.578878 -0.790536 0.13795 0.596676 -0.790536 0.184452 0.641368 -0.744731 0.150328 0.650213 -0.744731 0.106057 0.603162 -0.790536 0.115573 0.657281 -0.744731 0.0803283 0.662513 -0.744731 0.0656585 0.541523 -0.838118 -0.0574156 0.609717 -0.790537 -0.0899336 0.605775 -0.790537 -0.122068 0.600126 -0.790537 -0.184667 0.583909 -0.790537 -0.167477 0.646009 -0.744731 -0.201237 0.636302 -0.744731 -0.234174 0.624931 -0.744731 -0.191409 0.510804 -0.838118 -0.300037 0.533882 -0.790537 -0.355577 0.564749 -0.744731 -0.382922 0.546578 -0.744731 -0.312991 0.44676 -0.838118 -0.433605 0.50731 -0.744731 -0.456881 0.486453 -0.744731 -0.373444 0.397615 -0.838118 -0.499236 0.442876 -0.744731 -0.518321 0.42038 -0.744731 -0.475643 0.385766 -0.790536 -0.536031 0.397551 -0.744731 -0.552391 0.374487 -0.744731 -0.506908 0.343652 -0.790536 -0.567432 0.351279 -0.744731 -0.581193 0.328011 -0.744731 -0.533338 0.301003 -0.790536 -0.475053 0.268108 -0.838118 -0.485288 0.249104 -0.838118 -0.494549 0.230172 -0.838118 -0.502875 0.211364 -0.838118 -0.695423 0.157668 -0.70109 -0.733168 0.166225 -0.65942 -0.70016 0.135088 -0.70109 -0.522672 0.156116 -0.838118 -0.527689 0.138212 -0.838118 -0.531987 0.120613 -0.838118 -0.535611 0.10334 -0.838118 -0.538601 0.086413 -0.838118 -0.544175 0.0378356 -0.838118 -0.545028 0.0224079 -0.838118 -0.545439 0.00737116 -0.838118 -0.545439 -0.00737106 -0.838118 -0.545028 -0.022408 -0.838118 -0.544175 -0.0378356 -0.838118 -0.542844 -0.0536502 -0.838118 -0.658938 -0.10572 -0.744731 -0.65528 -0.126429 -0.744731 -0.601325 -0.116019 -0.790537 -0.540999 -0.0698456 -0.838118 -0.538601 -0.086413 -0.838118 -0.535611 -0.10334 -0.838118 -0.531987 -0.120613 -0.838118 -0.527689 -0.138212 -0.838118 -0.522672 -0.156116 -0.838118 -0.510309 -0.192725 -0.838118 -0.502875 -0.211364 -0.838118 -0.581193 -0.328011 -0.744731 -0.567432 -0.351279 -0.744731 -0.520711 -0.322355 -0.790537 -0.552391 -0.374487 -0.744731 -0.536031 -0.397551 -0.744731 -0.491895 -0.364817 -0.790537 -0.518321 -0.42038 -0.744731 -0.499236 -0.442876 -0.744731 -0.408064 -0.361997 -0.838118 -0.456881 -0.486453 -0.744731 -0.433605 -0.50731 -0.744731 -0.354418 -0.414663 -0.838118 -0.351392 -0.501573 -0.790536 -0.355577 -0.564749 -0.744731 -0.326959 -0.581785 -0.744731 -0.267248 -0.475538 -0.838118 -0.244257 -0.561596 -0.790536 -0.214893 -0.573475 -0.790536 -0.153687 -0.592817 -0.790536 -0.201237 -0.636302 -0.744731 -0.167477 -0.646009 -0.744731 -0.122068 -0.600126 -0.790536 -0.133021 -0.653974 -0.744731 -0.098003 -0.66013 -0.744731 -0.0801054 -0.539575 -0.838118 0.0737141 -0.607962 -0.790536 0.106057 -0.603162 -0.790536 0.13795 -0.596676 -0.790536 0.199881 -0.578878 -0.790536 0.184452 -0.641368 -0.744731 0.217816 -0.630819 -0.744731 0.250298 -0.618649 -0.744731 0.204588 -0.505669 -0.838118 0.286487 -0.541274 -0.790537 0.341423 -0.573416 -0.744731 0.369411 -0.555798 -0.744731 0.301948 -0.454296 -0.838118 0.386745 -0.474848 -0.790537 0.445417 -0.496971 -0.744731 0.467995 -0.47577 -0.744731 0.429461 -0.436595 -0.790537 0.448894 -0.416588 -0.790537 0.416006 -0.352842 -0.838118 0.444962 -0.315542 -0.838118 0.587606 -0.316379 -0.744731 0.599525 -0.293165 -0.744731 0.550161 -0.269026 -0.790536 0.490038 -0.239626 -0.838118 0.498826 -0.22075 -0.838118 0.506701 -0.20202 -0.838118 0.513705 -0.183482 -0.838118 0.51988 -0.165174 -0.838118 0.525272 -0.147128 -0.838118 0.529925 -0.129373 -0.838118 0.610263 -0.0513011 -0.790536 0.545287 -0.0148405 -0.838118 0.544659 -0.0300731 -0.838118 0.611483 0.0337627 -0.790537 0.74695 0.0850341 -0.65942 0.705729 0.102072 -0.70109 0.603089 0.106468 -0.790537 0.599383 0.125668 -0.790537 0.594942 0.145246 -0.790537 0.589719 0.165179 -0.790537 0.583665 0.185439 -0.790537 0.705453 0.344963 -0.619141 0.661927 0.356396 -0.65942 0.675355 0.330245 -0.65942 0.560027 0.247833 -0.790537 0.57447 0.339647 -0.744731 0.62785 0.338048 -0.70109 0.613815 0.36291 -0.70109 0.544378 0.386042 -0.744731 0.598434 0.38775 -0.70109 0.581662 0.412482 -0.70109 0.563465 0.437013 -0.70109 0.54381 0.461241 -0.70109 0.467045 0.396132 -0.790536 0.445417 0.496971 -0.744731 0.500048 0.508355 -0.70109 0.475924 0.531008 -0.70109 0.421446 0.517455 -0.744731 0.423229 0.57389 -0.70109 0.394713 0.593864 -0.70109 0.338995 0.510034 -0.790536 0.312192 0.589841 -0.744731 0.281789 0.604955 -0.744731 0.217816 0.630819 -0.744731 0.267441 0.661021 -0.70109 0.232734 0.674023 -0.70109 0.197085 0.685296 -0.70109 0.169265 0.588559 -0.790536 0.0447393 0.665864 -0.744731 0.00895755 0.667305 -0.744731 -0.026863 0.666824 -0.744731 -0.098003 0.66013 -0.744731 -0.0668526 0.709932 -0.70109 -0.104715 0.705342 -0.70109 -0.133021 0.653974 -0.744731 -0.142131 0.698764 -0.70109 -0.178948 0.690254 -0.70109 -0.153687 0.592817 -0.790537 -0.266174 0.611987 -0.744731 -0.297132 0.597569 -0.744731 -0.349352 0.621631 -0.70109 -0.37993 0.603428 -0.70109 -0.326299 0.518248 -0.790537 -0.408943 0.527391 -0.744731 -0.397902 0.465538 -0.790537 -0.511549 0.49678 -0.70109 -0.533429 0.473209 -0.70109 -0.45813 0.40641 -0.790536 -0.491895 0.364817 -0.790536 -0.520711 0.322355 -0.790536 -0.544829 0.279667 -0.790536 -0.555225 0.258412 -0.790536 -0.572919 0.21637 -0.790536 -0.580311 0.195682 -0.790536 -0.586799 0.17527 -0.790536 -0.592431 0.15517 -0.790536 -0.597257 0.135411 -0.790536 -0.601325 0.116019 -0.790536 -0.604682 0.097015 -0.790536 -0.607374 0.0784151 -0.790536 -0.609446 0.0602326 -0.790536 -0.61094 0.0424777 -0.790536 -0.611898 0.0251571 -0.790536 -0.612359 0.00827553 -0.790536 -0.612359 -0.00827542 -0.790536 -0.611898 -0.0251572 -0.790536 -0.61094 -0.0424777 -0.790536 -0.609446 -0.0602326 -0.790536 -0.607374 -0.078415 -0.790537 -0.604682 -0.097015 -0.790537 -0.597257 -0.135411 -0.790537 -0.592431 -0.15517 -0.790537 -0.698616 -0.358608 -0.619141 -0.711947 -0.331353 -0.619141 -0.738958 -0.343924 -0.57936 -0.572919 -0.21637 -0.790537 -0.646483 -0.300885 -0.70109 -0.634378 -0.325634 -0.70109 -0.593714 -0.304761 -0.744731 -0.544829 -0.279667 -0.790537 -0.533338 -0.301003 -0.790537 -0.506908 -0.343652 -0.790537 -0.475643 -0.385766 -0.790537 -0.511549 -0.49678 -0.70109 -0.488172 -0.519769 -0.70109 -0.419262 -0.446399 -0.790536 -0.408943 -0.527391 -0.744731 -0.409148 -0.584013 -0.70109 -0.37993 -0.603428 -0.70109 -0.326299 -0.518248 -0.790536 -0.297132 -0.597569 -0.744731 -0.234175 -0.624931 -0.744731 -0.284404 -0.653902 -0.70109 -0.250213 -0.667732 -0.70109 -0.21502 -0.679882 -0.70109 -0.184667 -0.583909 -0.790536 -0.0625675 -0.664426 -0.744731 -0.0268628 -0.666824 -0.744731 0.00895744 -0.667305 -0.744731 0.044739 -0.665864 -0.744731 0.115573 -0.657281 -0.744731 0.0858299 -0.707888 -0.70109 0.123489 -0.702299 -0.70109 0.150328 -0.650213 -0.744731 0.160624 -0.694747 -0.70109 0.197085 -0.685296 -0.70109 0.169265 -0.588559 -0.790536 0.281789 -0.604955 -0.744731 0.333574 -0.630239 -0.70109 0.364807 -0.612689 -0.70109 0.313311 -0.526202 -0.790537 0.3961 -0.537104 -0.744731 0.450311 -0.552895 -0.70109 0.475923 -0.531008 -0.70109 0.408742 -0.456051 -0.790537 0.508952 -0.431676 -0.744731 0.522675 -0.48506 -0.70109 0.54381 -0.461241 -0.70109 0.544378 -0.386042 -0.744731 0.563465 -0.437013 -0.70109 0.581662 -0.412482 -0.70109 0.57447 -0.339647 -0.744731 0.598434 -0.38775 -0.70109 0.613815 -0.36291 -0.70109 0.527169 -0.311681 -0.790537 0.539223 -0.290329 -0.790537 0.560028 -0.247833 -0.790536 0.568868 -0.226806 -0.790536 0.583665 -0.185439 -0.790536 0.589719 -0.165179 -0.790536 0.665019 -0.0559042 -0.744731 0.611484 -0.0337627 -0.790536 0.612188 -0.0166613 -0.790536 0.66635 0.0367921 -0.744731 0.660492 0.0955293 -0.744731 0.657203 0.116021 -0.744731 0.653164 0.136944 -0.744731 0.648324 0.158278 -0.744731 0.642632 0.18 -0.744731 0.628479 0.224477 -0.744731 0.619911 0.247157 -0.744731 0.610277 0.270071 -0.744731 0.599525 0.293165 -0.744731 0.587606 0.316379 -0.744731 0.560074 0.362895 -0.744731 0.527347 0.409001 -0.744731 0.551044 0.511387 -0.65942 0.522675 0.48506 -0.70109 0.467995 0.47577 -0.744731 0.474751 0.582904 -0.65942 0.450311 0.552895 -0.70109 0.3961 0.537104 -0.744731 0.364807 0.61269 -0.70109 0.351679 0.664445 -0.65942 0.301089 0.646389 -0.70109 0.333574 0.630239 -0.70109 0.31743 0.681472 -0.65942 0.250298 0.618649 -0.744731 0.160624 0.694747 -0.70109 0.123489 0.702299 -0.70109 0.08583 0.707888 -0.70109 0.050398 0.750084 -0.65942 0.00957105 0.713009 -0.70109 0.0478035 0.711469 -0.70109 0.0100905 0.751707 -0.65942 -0.0287028 0.712495 -0.70109 -0.0302607 0.751166 -0.65942 -0.0625674 0.664426 -0.744731 -0.21502 0.679882 -0.70109 -0.250213 0.667732 -0.70109 -0.29984 0.689392 -0.65942 -0.317483 0.638496 -0.70109 -0.284404 0.653901 -0.70109 -0.334714 0.673151 -0.65942 -0.326959 0.581785 -0.744731 -0.409148 0.584013 -0.70109 -0.460667 0.594097 -0.65942 -0.463302 0.542055 -0.70109 -0.436952 0.563512 -0.70109 -0.488172 0.519769 -0.70109 -0.478759 0.464937 -0.744731 -0.58388 0.47355 -0.65942 -0.572744 0.424779 -0.70109 -0.553821 0.449171 -0.70109 -0.622259 0.421852 -0.65942 -0.606296 0.375337 -0.70109 -0.590224 0.400135 -0.70109 -0.788096 0.297635 -0.538812 -0.800667 0.336529 -0.495662 -0.812503 0.306853 -0.495662 -0.593714 0.304761 -0.744731 -0.807189 0.241098 -0.538812 -0.814937 0.213448 -0.538812 -0.788475 0.206517 -0.57936 -0.624325 0.235785 -0.744731 -0.63238 0.213239 -0.744731 -0.63945 0.190996 -0.744731 -0.645588 0.169092 -0.744731 -0.650847 0.147561 -0.744731 -0.65528 0.126429 -0.744731 -0.658938 0.10572 -0.744731 -0.661872 0.085451 -0.744731 -0.664129 0.0656371 -0.744731 -0.665758 0.046289 -0.744731 -0.666802 0.0274144 -0.744731 -0.667304 0.00901807 -0.744731 -0.667304 -0.00901795 -0.744731 -0.666802 -0.0274145 -0.744731 -0.665758 -0.0462891 -0.744731 -0.664129 -0.0656371 -0.744731 -0.661872 -0.0854509 -0.744731 -0.762506 -0.287971 -0.57936 -0.798264 -0.269176 -0.538812 -0.788096 -0.297635 -0.538812 -0.650847 -0.147561 -0.744731 -0.645588 -0.169092 -0.744731 -0.63945 -0.190996 -0.744731 -0.63238 -0.21324 -0.744731 -0.624325 -0.235785 -0.744731 -0.615231 -0.258588 -0.744731 -0.605044 -0.281599 -0.744731 -0.639203 -0.395709 -0.65942 -0.590224 -0.400135 -0.70109 -0.606296 -0.375337 -0.70109 -0.60383 -0.447834 -0.65942 -0.553821 -0.449171 -0.70109 -0.572744 -0.424779 -0.70109 -0.533428 -0.473209 -0.70109 -0.478759 -0.464937 -0.744731 -0.463302 -0.542055 -0.70109 -0.460668 -0.594097 -0.65942 -0.436952 -0.563512 -0.70109 -0.382922 -0.546578 -0.744731 -0.349352 -0.621632 -0.70109 -0.334714 -0.673151 -0.65942 -0.317483 -0.638496 -0.70109 -0.266174 -0.611987 -0.744731 -0.178948 -0.690254 -0.70109 -0.142131 -0.698764 -0.70109 -0.104715 -0.705342 -0.70109 -0.0704812 -0.748464 -0.65942 -0.0287027 -0.712495 -0.70109 -0.0668527 -0.709932 -0.70109 -0.0302605 -0.751166 -0.65942 0.00957093 -0.713009 -0.70109 0.0100904 -0.751707 -0.65942 0.0478032 -0.711469 -0.70109 0.0503977 -0.750084 -0.65942 0.0803282 -0.662513 -0.744731 0.232734 -0.674024 -0.70109 0.267441 -0.66102 -0.70109 0.317431 -0.681472 -0.65942 0.301089 -0.646389 -0.70109 0.312192 -0.589841 -0.744731 0.394712 -0.593864 -0.70109 0.4462 -0.605038 -0.65942 0.423229 -0.57389 -0.70109 0.421446 -0.517455 -0.744731 0.527188 -0.535946 -0.65942 0.500048 -0.508355 -0.70109 0.489172 -0.453968 -0.744731 0.527347 -0.409 -0.744731 0.560074 -0.362895 -0.744731 0.802878 -0.255086 -0.538812 0.817909 -0.292137 -0.495662 0.827743 -0.262986 -0.495662 0.610277 -0.270071 -0.744731 0.723914 -0.202767 -0.65942 0.756177 -0.211803 -0.619141 0.730326 -0.178298 -0.65942 0.636035 -0.202078 -0.744731 0.642632 -0.18 -0.744731 0.648324 -0.158278 -0.744731 0.653163 -0.136944 -0.744731 0.702214 -0.123967 -0.70109 0.667118 -0.0181563 -0.744731 0.66635 -0.0367922 -0.744731 0.743643 3.97332e-16 -0.668577 0.711988 0.039312 -0.70109 0.702214 0.123967 -0.70109 0.697898 0.146323 -0.70109 0.692727 0.169119 -0.70109 0.716482 0.227637 -0.65942 0.671524 0.239851 -0.70109 0.662368 0.264085 -0.70109 0.652075 0.288568 -0.70109 0.640586 0.313243 -0.70109 0.684035 0.443214 -0.57936 0.640563 0.454251 -0.619141 0.659032 0.427014 -0.619141 0.644064 0.499524 -0.57936 0.598877 0.507947 -0.619141 0.620522 0.481265 -0.619141 0.573325 0.486275 -0.65942 0.501754 0.559829 -0.65942 0.524116 0.584779 -0.619141 0.416136 0.626096 -0.65942 0.434682 0.654 -0.619141 0.384607 0.645944 -0.65942 0.401748 0.674731 -0.619141 0.281956 0.696898 -0.65942 0.207782 0.72249 -0.65942 0.217043 0.75469 -0.619141 0.169342 0.732454 -0.65942 0.176889 0.765098 -0.619141 0.130191 0.740416 -0.65942 0.135993 0.773414 -0.619141 0.0904884 0.746309 -0.65942 0.0945212 0.77957 -0.619141 -0.070481 0.748464 -0.65942 -0.110399 0.743625 -0.65942 -0.18866 0.727718 -0.65942 -0.197068 0.76015 -0.619141 -0.22669 0.716783 -0.65942 -0.236793 0.748728 -0.619141 -0.263793 0.703974 -0.65942 -0.27555 0.735348 -0.619141 -0.400551 0.63618 -0.65942 -0.418402 0.664533 -0.619141 -0.431354 0.61571 -0.65942 -0.499454 0.644118 -0.57936 -0.510217 0.596944 -0.619141 -0.481198 0.620574 -0.619141 -0.584722 0.567841 -0.57936 -0.587444 0.521127 -0.619141 -0.563349 0.547085 -0.619141 -0.562381 0.498892 -0.65942 -0.620998 0.350476 -0.70109 -0.634378 0.325634 -0.70109 -0.646483 0.300885 -0.70109 -0.657367 0.276298 -0.70109 -0.667085 0.251934 -0.70109 -0.675692 0.227844 -0.70109 -0.683246 0.204077 -0.70109 -0.689804 0.180674 -0.70109 -0.704069 0.112961 -0.70109 -0.707203 0.0913036 -0.70109 -0.709616 0.0701325 -0.70109 -0.711356 0.0494594 -0.70109 -0.712471 0.029292 -0.70109 -0.713008 0.00963572 -0.70109 -0.713008 -0.00963559 -0.70109 -0.712471 -0.0292921 -0.70109 -0.711356 -0.0494594 -0.70109 -0.709616 -0.0701326 -0.70109 -0.707203 -0.0913034 -0.70109 -0.704069 -0.112961 -0.70109 -0.70016 -0.135088 -0.70109 -0.695423 -0.157667 -0.70109 -0.689804 -0.180674 -0.70109 -0.683246 -0.204077 -0.70109 -0.675692 -0.227844 -0.70109 -0.667085 -0.251933 -0.70109 -0.657367 -0.276298 -0.70109 -0.738462 -0.457157 -0.495662 -0.718887 -0.48736 -0.495662 -0.697293 -0.472721 -0.538812 -0.620998 -0.350476 -0.70109 -0.584722 -0.567841 -0.57936 -0.537606 -0.572402 -0.619141 -0.563349 -0.547085 -0.619141 -0.514668 -0.54798 -0.65942 -0.488448 -0.571475 -0.65942 -0.499454 -0.644118 -0.57936 -0.450579 -0.643151 -0.619141 -0.481198 -0.620574 -0.619141 -0.400551 -0.63618 -0.65942 -0.418402 -0.664533 -0.619141 -0.368313 -0.655371 -0.65942 -0.362896 -0.729828 -0.57936 -0.313203 -0.720116 -0.619141 -0.349631 -0.703151 -0.619141 -0.29984 -0.689392 -0.65942 -0.22669 -0.716783 -0.65942 -0.236793 -0.748728 -0.619141 -0.18866 -0.727718 -0.65942 -0.197068 -0.76015 -0.619141 -0.149845 -0.73669 -0.65942 -0.156524 -0.769522 -0.619141 -0.110399 -0.743625 -0.65942 -0.115319 -0.776766 -0.619141 0.0904883 -0.746309 -0.65942 0.169342 -0.732454 -0.65942 0.176889 -0.765098 -0.619141 0.207782 -0.72249 -0.65942 0.217043 -0.75469 -0.619141 0.245366 -0.710606 -0.65942 0.256301 -0.742276 -0.619141 0.281957 -0.696897 -0.65942 0.367352 -0.694058 -0.619141 0.331578 -0.711843 -0.619141 0.344157 -0.738849 -0.57936 0.351679 -0.664445 -0.65942 0.416136 -0.626097 -0.65942 0.434682 -0.654 -0.619141 0.501754 -0.559829 -0.65942 0.524116 -0.584779 -0.619141 0.644064 -0.499524 -0.57936 0.640563 -0.454251 -0.619141 0.620522 -0.481265 -0.619141 0.684035 -0.443214 -0.57936 0.675971 -0.399659 -0.619141 0.659032 -0.427014 -0.619141 0.780228 -0.381527 -0.495662 0.794221 -0.351473 -0.495662 0.770363 -0.340915 -0.538812 0.62785 -0.338048 -0.70109 0.640587 -0.313243 -0.70109 0.652075 -0.288568 -0.70109 0.662368 -0.264085 -0.70109 0.671524 -0.239851 -0.70109 0.679597 -0.215918 -0.70109 0.686646 -0.192328 -0.70109 0.692727 -0.169119 -0.70109 0.697898 -0.146323 -0.70109 0.78252 -0.0657817 -0.619141 0.78024 -0.0888237 -0.619141 0.712809 -0.0193998 -0.70109 0.750632 0.0414457 -0.65942 0.744033 0.107612 -0.65942 0.756177 0.211803 -0.619141 0.762874 0.186244 -0.619141 0.791817 0.19331 -0.57936 0.740327 0.130695 -0.65942 0.735777 0.154265 -0.65942 0.730326 0.178298 -0.65942 0.723914 0.202766 -0.65942 0.794221 0.351473 -0.495662 0.780228 0.381527 -0.495662 0.756791 0.370067 -0.538812 0.707971 0.252869 -0.65942 0.698319 0.278418 -0.65942 0.687466 0.30423 -0.65942 0.64713 0.382607 -0.65942 0.630914 0.408795 -0.65942 0.613232 0.43487 -0.65942 0.594047 0.460732 -0.65942 0.562257 0.627334 -0.538812 0.544001 0.606964 -0.57936 0.590758 0.600572 -0.538812 0.527188 0.535946 -0.65942 0.466086 0.632003 -0.619141 0.483769 0.65598 -0.57936 0.4462 0.605038 -0.65942 0.331577 0.711843 -0.619141 0.344157 0.738849 -0.57936 0.294522 0.727956 -0.619141 0.305696 0.755574 -0.57936 0.256301 0.742276 -0.619141 0.232837 0.80961 -0.538812 0.225277 0.783321 -0.57936 0.274953 0.796293 -0.538812 0.245366 0.710606 -0.65942 0.0105402 0.785209 -0.619141 0.0109401 0.814998 -0.57936 -0.0316093 0.784643 -0.619141 -0.0328085 0.814411 -0.57936 -0.0736222 0.781821 -0.619141 -0.0764153 0.811482 -0.57936 -0.115319 0.776766 -0.619141 -0.119694 0.806235 -0.57936 -0.156524 0.769522 -0.619141 -0.162462 0.798717 -0.57936 -0.149845 0.73669 -0.65942 -0.349631 0.703151 -0.619141 -0.362896 0.729828 -0.57936 -0.384728 0.684579 -0.619141 -0.399324 0.710551 -0.57936 -0.368313 0.655371 -0.65942 -0.576728 0.614057 -0.538812 -0.558002 0.594118 -0.57936 -0.547347 0.640385 -0.538812 -0.488448 0.571475 -0.65942 -0.514668 0.54798 -0.65942 -0.539313 0.523743 -0.65942 -0.716279 0.443425 -0.538812 -0.718887 0.487361 -0.495662 -0.738462 0.457157 -0.495662 -0.60383 0.447834 -0.65942 -0.749456 0.384705 -0.538812 -0.75637 0.426877 -0.495662 -0.772666 0.396619 -0.495662 -0.639203 0.395709 -0.65942 -0.654703 0.369499 -0.65942 -0.668809 0.343308 -0.65942 -0.681571 0.317216 -0.65942 -0.693046 0.291295 -0.65942 -0.703291 0.265607 -0.65942 -0.712365 0.24021 -0.65942 -0.720329 0.215154 -0.65942 -0.727244 0.19048 -0.65942 -0.775364 0.124399 -0.619141 -0.745587 0.0962591 -0.65942 -0.742282 0.119092 -0.65942 -0.738161 0.14242 -0.65942 -0.74813 0.073939 -0.65942 -0.749964 0.0521438 -0.65942 -0.75114 0.0308818 -0.65942 -0.751706 0.0101587 -0.65942 -0.751706 -0.0101586 -0.65942 -0.75114 -0.030882 -0.65942 -0.749964 -0.0521438 -0.65942 -0.74813 -0.073939 -0.65942 -0.745587 -0.0962589 -0.65942 -0.742282 -0.119092 -0.65942 -0.738161 -0.14242 -0.65942 -0.733168 -0.166225 -0.65942 -0.727244 -0.19048 -0.65942 -0.720329 -0.215154 -0.65942 -0.712365 -0.240211 -0.65942 -0.703291 -0.265607 -0.65942 -0.693046 -0.291295 -0.65942 -0.681572 -0.317216 -0.65942 -0.668809 -0.343308 -0.65942 -0.654703 -0.369499 -0.65942 -0.654286 -0.530652 -0.538812 -0.697597 -0.517376 -0.495662 -0.674549 -0.547086 -0.495662 -0.622259 -0.421852 -0.65942 -0.630194 -0.55905 -0.538812 -0.609731 -0.540898 -0.57936 -0.58388 -0.47355 -0.65942 -0.562381 -0.498892 -0.65942 -0.539313 -0.523743 -0.65942 -0.448851 -0.712892 -0.538812 -0.434276 -0.689744 -0.57936 -0.483368 -0.689954 -0.538812 -0.431354 -0.61571 -0.65942 -0.325086 -0.747437 -0.57936 -0.27555 -0.735348 -0.619141 -0.286004 -0.763246 -0.57936 -0.263793 -0.703973 -0.65942 -0.0316092 -0.784643 -0.619141 -0.0328083 -0.814411 -0.57936 0.0105401 -0.785209 -0.619141 0.01094 -0.814998 -0.57936 0.0526438 -0.783513 -0.619141 0.0546411 -0.813238 -0.57936 0.0945211 -0.77957 -0.619141 0.0981071 -0.809146 -0.57936 0.135994 -0.773414 -0.619141 0.141153 -0.802756 -0.57936 0.130191 -0.740416 -0.65942 0.381289 -0.720389 -0.57936 0.401748 -0.674732 -0.619141 0.466314 -0.701593 -0.538812 0.451173 -0.678812 -0.57936 0.430984 -0.723833 -0.538812 0.384607 -0.645944 -0.65942 0.49591 -0.608882 -0.619141 0.514724 -0.631982 -0.57936 0.474752 -0.582904 -0.65942 0.642459 -0.544912 -0.538812 0.621598 -0.527218 -0.57936 0.61749 -0.573051 -0.538812 0.551044 -0.511387 -0.65942 0.573325 -0.486275 -0.65942 0.594047 -0.460732 -0.65942 0.613232 -0.43487 -0.65942 0.630914 -0.408795 -0.65942 0.64713 -0.382607 -0.65942 0.661927 -0.356396 -0.65942 0.675355 -0.330245 -0.65942 0.687466 -0.30423 -0.65942 0.698319 -0.278418 -0.65942 0.707971 -0.252869 -0.65942 0.716482 -0.227637 -0.65942 0.735777 -0.154265 -0.65942 0.750632 -0.0414457 -0.65942 0.751497 -0.0204528 -0.65942 0.78252 0.0657818 -0.619141 0.784086 0.0432928 -0.619141 0.78024 0.0888238 -0.619141 0.777193 0.112408 -0.619141 0.773322 0.13652 -0.619141 0.768569 0.16114 -0.619141 0.748414 0.237782 -0.619141 0.739523 0.264139 -0.619141 0.729441 0.290826 -0.619141 0.718105 0.317789 -0.619141 0.747621 0.44202 -0.495662 0.725163 0.428742 -0.538812 0.764716 0.411739 -0.495662 0.691428 0.372279 -0.619141 0.675971 0.399658 -0.619141 0.609053 0.619172 -0.495662 0.636613 0.590798 -0.495662 0.575602 0.534178 -0.619141 0.550683 0.559832 -0.619141 0.515489 0.698992 -0.495662 0.500004 0.677995 -0.538812 0.548474 0.673421 -0.495662 0.49591 0.608882 -0.619141 0.466314 0.701593 -0.538812 0.430984 0.723833 -0.538812 0.41699 0.70033 -0.57936 0.366723 0.787295 -0.495662 0.355707 0.763645 -0.538812 0.40629 0.767625 -0.495662 0.367352 0.694058 -0.619141 0.189761 0.820776 -0.538812 0.1836 0.794124 -0.57936 0.14589 0.829697 -0.538812 0.141153 0.802756 -0.57936 0.1014 0.836301 -0.538812 0.0981072 0.809146 -0.57936 0.0116574 0.868437 -0.495662 0.0113073 0.84235 -0.538812 0.0582242 0.866562 -0.495662 0.0526441 0.783513 -0.619141 -0.211409 0.815468 -0.538812 -0.254025 0.803214 -0.538812 -0.245777 0.777133 -0.57936 -0.295602 0.788861 -0.538812 -0.286004 0.763246 -0.57936 -0.386691 0.777682 -0.495662 -0.375075 0.754321 -0.538812 -0.346401 0.796445 -0.495662 -0.313203 0.720116 -0.619141 -0.44885 0.712892 -0.538812 -0.483368 0.689954 -0.538812 -0.467673 0.667551 -0.57936 -0.450579 0.643151 -0.619141 -0.537606 0.572402 -0.619141 -0.697597 0.517376 -0.495662 -0.676641 0.501835 -0.538812 -0.674549 0.547086 -0.495662 -0.609902 0.494655 -0.619141 -0.630741 0.467793 -0.619141 -0.649991 0.440653 -0.619141 -0.66769 0.413345 -0.619141 -0.683882 0.385966 -0.619141 -0.698616 0.358608 -0.619141 -0.711947 0.331354 -0.619141 -0.723933 0.304277 -0.619141 -0.734635 0.277445 -0.619141 -0.744114 0.250916 -0.619141 -0.752433 0.224743 -0.619141 -0.759655 0.198969 -0.619141 -0.765843 0.173633 -0.619141 -0.771059 0.148768 -0.619141 -0.778816 0.100549 -0.619141 -0.781472 0.0772343 -0.619141 -0.785208 0.0106114 -0.619141 -0.784617 0.0322581 -0.619141 -0.814384 0.0334819 -0.57936 -0.783388 0.0544677 -0.619141 -0.785208 -0.0106113 -0.619141 -0.784617 -0.0322583 -0.619141 -0.783388 -0.0544677 -0.619141 -0.775364 -0.124399 -0.619141 -0.778816 -0.100549 -0.619141 -0.808363 -0.104364 -0.57936 -0.781472 -0.0772343 -0.619141 -0.771059 -0.148768 -0.619141 -0.765843 -0.173633 -0.619141 -0.759655 -0.198969 -0.619141 -0.752433 -0.224743 -0.619141 -0.744114 -0.250916 -0.619141 -0.734635 -0.277445 -0.619141 -0.723934 -0.304277 -0.619141 -0.683882 -0.385966 -0.619141 -0.66769 -0.413345 -0.619141 -0.649991 -0.440653 -0.619141 -0.630741 -0.467793 -0.619141 -0.609902 -0.494655 -0.619141 -0.587444 -0.521127 -0.619141 -0.576728 -0.614057 -0.538812 -0.547347 -0.640386 -0.538812 -0.529574 -0.619592 -0.57936 -0.510217 -0.596945 -0.619141 -0.412725 -0.734397 -0.538812 -0.399324 -0.710551 -0.57936 -0.384728 -0.684579 -0.619141 -0.254025 -0.803214 -0.538812 -0.211409 -0.815468 -0.538812 -0.204544 -0.788989 -0.57936 -0.167914 -0.825522 -0.538812 -0.162462 -0.798717 -0.57936 -0.123711 -0.833293 -0.538812 -0.119694 -0.806235 -0.57936 -0.07898 -0.838716 -0.538812 -0.0764154 -0.811482 -0.57936 -0.0736223 -0.781821 -0.619141 0.189761 -0.820776 -0.538812 0.232837 -0.80961 -0.538812 0.225277 -0.783321 -0.57936 0.274953 -0.796293 -0.538812 0.266025 -0.770437 -0.57936 0.315956 -0.780931 -0.538812 0.305696 -0.755574 -0.57936 0.294523 -0.727956 -0.619141 0.548474 -0.673421 -0.495662 0.531998 -0.653192 -0.538812 0.515489 -0.698992 -0.495662 0.466086 -0.632003 -0.619141 0.636614 -0.590798 -0.495662 0.609053 -0.619172 -0.495662 0.550683 -0.559832 -0.619141 0.575603 -0.534178 -0.619141 0.598877 -0.507947 -0.619141 0.691428 -0.372279 -0.619141 0.705454 -0.344963 -0.619141 0.718105 -0.317789 -0.619141 0.729441 -0.290826 -0.619141 0.739523 -0.264139 -0.619141 0.748414 -0.237782 -0.619141 0.773322 -0.13652 -0.619141 0.768569 -0.16114 -0.619141 0.797727 -0.167253 -0.57936 0.762874 -0.186244 -0.619141 0.777193 -0.112408 -0.619141 0.809841 -0.0921935 -0.57936 0.784989 -0.0213643 -0.619141 0.784085 -0.0432928 -0.619141 0.813832 0.0449353 -0.57936 0.806678 0.116673 -0.57936 0.80266 0.141699 -0.57936 0.797727 0.167253 -0.57936 0.844319 0.295444 -0.447033 0.817909 0.292137 -0.495662 0.827743 0.262986 -0.495662 0.784865 0.219839 -0.57936 0.776808 0.246803 -0.57936 0.76758 0.27416 -0.57936 0.757115 0.30186 -0.57936 0.745349 0.329845 -0.57936 0.732217 0.35805 -0.57936 0.717659 0.386403 -0.57936 0.701617 0.414821 -0.57936 0.686294 0.532277 -0.495662 0.714727 0.53789 -0.447033 0.69936 0.557725 -0.447033 0.664865 0.471484 -0.57936 0.662355 0.561787 -0.495662 0.642458 0.544912 -0.538812 0.621597 0.527218 -0.57936 0.59744 0.554444 -0.57936 0.571575 0.581071 -0.57936 0.514724 0.631982 -0.57936 0.480756 0.723321 -0.495662 0.451173 0.678812 -0.57936 0.381289 0.720389 -0.57936 0.32574 0.805116 -0.495662 0.315955 0.780931 -0.538812 0.283468 0.820954 -0.495662 0.266025 0.770437 -0.57936 0.0546414 0.813238 -0.57936 -0.0349598 0.867812 -0.495662 -0.0339096 0.841743 -0.538812 -0.0814258 0.86469 -0.495662 -0.0789798 0.838716 -0.538812 -0.127542 0.8591 -0.495662 -0.123711 0.833293 -0.538812 -0.173114 0.851088 -0.495662 -0.167914 0.825522 -0.538812 -0.217956 0.840723 -0.495662 -0.204545 0.788989 -0.57936 -0.325086 0.747437 -0.57936 -0.425507 0.757141 -0.495662 -0.412726 0.734397 -0.538812 -0.462751 0.73497 -0.495662 -0.434276 0.689744 -0.57936 -0.532203 0.686352 -0.495662 -0.564298 0.660218 -0.495662 -0.529574 0.619592 -0.57936 -0.623061 0.605074 -0.495662 -0.649711 0.576364 -0.495662 -0.630194 0.55905 -0.538812 -0.609731 0.540897 -0.57936 -0.633041 0.513422 -0.57936 -0.65467 0.48554 -0.57936 -0.674651 0.457371 -0.57936 -0.693021 0.429027 -0.57936 -0.709827 0.400609 -0.57936 -0.72512 0.372213 -0.57936 -0.738958 0.343925 -0.57936 -0.751398 0.315821 -0.57936 -0.762506 0.287971 -0.57936 -0.772344 0.260435 -0.57936 -0.780979 0.233269 -0.57936 -0.794898 0.180221 -0.57936 -0.800312 0.154412 -0.57936 -0.80478 0.129119 -0.57936 -0.808363 0.104364 -0.57936 -0.81112 0.0801644 -0.57936 -0.813109 0.0565341 -0.57936 -0.814997 0.011014 -0.57936 -0.814997 -0.0110139 -0.57936 -0.814384 -0.0334821 -0.57936 -0.813109 -0.0565341 -0.57936 -0.81112 -0.0801644 -0.57936 -0.80478 -0.129119 -0.57936 -0.866163 -0.223434 -0.447033 -0.840175 -0.220059 -0.495662 -0.847019 -0.192037 -0.495662 -0.800312 -0.154412 -0.57936 -0.794898 -0.18022 -0.57936 -0.788475 -0.206517 -0.57936 -0.780979 -0.233269 -0.57936 -0.772344 -0.260436 -0.57936 -0.751399 -0.315821 -0.57936 -0.75637 -0.426877 -0.495662 -0.772666 -0.396619 -0.495662 -0.782902 -0.432696 -0.447033 -0.72512 -0.372213 -0.57936 -0.709827 -0.400609 -0.57936 -0.693021 -0.429027 -0.57936 -0.674651 -0.457371 -0.57936 -0.65467 -0.48554 -0.57936 -0.633041 -0.513422 -0.57936 -0.623061 -0.605074 -0.495662 -0.594589 -0.633074 -0.495662 -0.558002 -0.594118 -0.57936 -0.532203 -0.686352 -0.495662 -0.498338 -0.711322 -0.495662 -0.467673 -0.667551 -0.57936 -0.386691 -0.777682 -0.495662 -0.346401 -0.796445 -0.495662 -0.335996 -0.772521 -0.538812 -0.304757 -0.813291 -0.495662 -0.295602 -0.788861 -0.538812 -0.261892 -0.828089 -0.495662 -0.245777 -0.777133 -0.57936 -0.0349596 -0.867812 -0.495662 0.0116573 -0.868437 -0.495662 0.0113071 -0.84235 -0.538812 0.0582238 -0.866562 -0.495662 0.0564748 -0.840531 -0.538812 0.10454 -0.862201 -0.495662 0.1014 -0.836301 -0.538812 0.150408 -0.855393 -0.495662 0.14589 -0.829697 -0.538812 0.195638 -0.846194 -0.495662 0.1836 -0.794124 -0.57936 0.366723 -0.787295 -0.495662 0.40629 -0.767625 -0.495662 0.394085 -0.744566 -0.538812 0.444331 -0.74625 -0.495662 0.41699 -0.70033 -0.57936 0.483769 -0.65598 -0.57936 0.57967 -0.646763 -0.495662 0.562257 -0.627334 -0.538812 0.544001 -0.606964 -0.57936 0.571575 -0.581071 -0.57936 0.59744 -0.554444 -0.57936 0.686295 -0.532277 -0.495662 0.708459 -0.502399 -0.495662 0.687178 -0.487307 -0.538812 0.664865 -0.471484 -0.57936 0.764716 -0.411739 -0.495662 0.747621 -0.44202 -0.495662 0.782904 -0.432693 -0.447033 0.701617 -0.414821 -0.57936 0.717659 -0.386403 -0.57936 0.732217 -0.35805 -0.57936 0.745349 -0.329845 -0.57936 0.757115 -0.30186 -0.57936 0.76758 -0.27416 -0.57936 0.776808 -0.246803 -0.57936 0.784865 -0.219839 -0.57936 0.791817 -0.19331 -0.57936 0.829598 -0.146455 -0.538812 0.833751 -0.120588 -0.538812 0.806678 -0.116673 -0.57936 0.80266 -0.141699 -0.57936 0.813832 -0.0449353 -0.57936 0.862942 0.0982387 -0.495662 0.83702 0.0952877 -0.538812 0.865463 0.0727543 -0.495662 0.833751 0.120588 -0.538812 0.829598 0.146455 -0.538812 0.824499 0.172866 -0.538812 0.81839 0.199797 -0.538812 0.811206 0.227217 -0.538812 0.802878 0.255086 -0.538812 0.79334 0.283361 -0.538812 0.782524 0.31199 -0.538812 0.770363 0.340915 -0.538812 0.741744 0.399371 -0.538812 0.706991 0.458089 -0.538812 0.687178 0.487307 -0.538812 0.665679 0.516288 -0.538812 0.61749 0.573051 -0.538812 0.557721 0.699363 -0.447033 0.577116 0.683446 -0.447033 0.531998 0.653192 -0.538812 0.410566 0.794731 -0.447033 0.432694 0.782903 -0.447033 0.394085 0.744566 -0.538812 0.240048 0.834683 -0.495662 0.149836 0.881879 -0.447033 0.150408 0.855393 -0.495662 0.174511 0.877329 -0.447033 0.100154 0.888893 -0.447033 0.10454 0.862201 -0.495662 0.125044 0.885734 -0.447033 0.0501544 0.89311 -0.447033 0.0751835 0.891352 -0.447033 0.0564752 0.840531 -0.538812 -0.319006 0.835701 -0.447033 -0.304757 0.813291 -0.495662 -0.295442 0.844319 -0.447033 -0.365361 0.8165 -0.447033 -0.342318 0.826426 -0.447033 -0.335996 0.772521 -0.538812 -0.557724 0.69936 -0.447033 -0.53789 0.714728 -0.447033 -0.516216 0.665735 -0.538812 -0.650011 0.61453 -0.447033 -0.632521 0.632518 -0.447033 -0.604345 0.586898 -0.538812 -0.654286 0.530652 -0.538812 -0.697293 0.472721 -0.538812 -0.733649 0.414054 -0.538812 -0.763757 0.355467 -0.538812 -0.776616 0.32642 -0.538812 -0.798265 0.269176 -0.538812 -0.847019 0.192038 -0.495662 -0.821575 0.186269 -0.538812 -0.840175 0.220059 -0.495662 -0.827171 0.159594 -0.538812 -0.831789 0.133452 -0.538812 -0.835492 0.107866 -0.538812 -0.838342 0.0828548 -0.538812 -0.840397 0.0584315 -0.538812 -0.841715 0.0346056 -0.538812 -0.842349 0.0113837 -0.538812 -0.842349 -0.0113835 -0.538812 -0.841715 -0.0346058 -0.538812 -0.840397 -0.0584315 -0.538812 -0.838342 -0.0828548 -0.538812 -0.835492 -0.107866 -0.538812 -0.831789 -0.133452 -0.538812 -0.827171 -0.159594 -0.538812 -0.821575 -0.186269 -0.538812 -0.814937 -0.213448 -0.538812 -0.807189 -0.241098 -0.538812 -0.800667 -0.336529 -0.495662 -0.776616 -0.32642 -0.538812 -0.812503 -0.306853 -0.495662 -0.763757 -0.355467 -0.538812 -0.749456 -0.384705 -0.538812 -0.733649 -0.414054 -0.538812 -0.716279 -0.443425 -0.538812 -0.676641 -0.501835 -0.538812 -0.632517 -0.632521 -0.447033 -0.650009 -0.614532 -0.447033 -0.604345 -0.586898 -0.538812 -0.537888 -0.714729 -0.447033 -0.557721 -0.699363 -0.447033 -0.516216 -0.665735 -0.538812 -0.432694 -0.782903 -0.447033 -0.425507 -0.757141 -0.495662 -0.454482 -0.770459 -0.447033 -0.388116 -0.805933 -0.447033 -0.410566 -0.794731 -0.447033 -0.375075 -0.754321 -0.538812 -0.174511 -0.87733 -0.447033 -0.173114 -0.851088 -0.495662 -0.199048 -0.87209 -0.447033 -0.125044 -0.885734 -0.447033 -0.127542 -0.8591 -0.495662 -0.149836 -0.881879 -0.447033 -0.0751838 -0.891352 -0.447033 -0.0814259 -0.86469 -0.495662 -0.100154 -0.888893 -0.447033 -0.0250868 -0.894165 -0.447033 -0.0501546 -0.89311 -0.447033 -0.0339094 -0.841743 -0.538812 0.295442 -0.844319 -0.447033 0.283468 -0.820954 -0.495662 0.271645 -0.852274 -0.447033 0.342318 -0.826426 -0.447033 0.325741 -0.805116 -0.495662 0.319006 -0.835701 -0.447033 0.388118 -0.805932 -0.447033 0.365361 -0.8165 -0.447033 0.355707 -0.763645 -0.538812 0.53789 -0.714728 -0.447033 0.517632 -0.729533 -0.447033 0.500004 -0.677995 -0.538812 0.590758 -0.600572 -0.538812 0.714729 -0.537888 -0.447033 0.699363 -0.557721 -0.447033 0.665679 -0.516288 -0.538812 0.706991 -0.458089 -0.538812 0.725163 -0.428743 -0.538812 0.741744 -0.399371 -0.538812 0.756791 -0.370067 -0.538812 0.782524 -0.31199 -0.538812 0.79334 -0.283361 -0.538812 0.811205 -0.227217 -0.538812 0.81839 -0.199797 -0.538812 0.824499 -0.172866 -0.538812 0.841145 -0.0464434 -0.538812 0.865463 -0.0727543 -0.495662 0.888892 0.100156 -0.447033 0.859572 0.124323 -0.495662 0.85529 0.15099 -0.495662 0.850034 0.17822 -0.495662 0.843735 0.205985 -0.495662 0.836328 0.234253 -0.495662 0.806758 0.321653 -0.495662 0.805931 0.38812 -0.447033 0.782902 0.432696 -0.447033 0.728886 0.472275 -0.495662 0.708459 0.502399 -0.495662 0.650009 0.614532 -0.447033 0.57967 0.646763 -0.495662 0.517631 0.729534 -0.447033 0.444331 0.74625 -0.495662 0.388115 0.805933 -0.447033 0.365361 0.8165 -0.447033 0.319003 0.835702 -0.447033 0.271644 0.852274 -0.447033 0.195638 0.846194 -0.495662 8.14756e-08 0.894517 -0.447033 0.0250868 0.894165 -0.447033 -0.0501575 0.89311 -0.447033 -0.100155 0.888893 -0.447033 -0.149839 0.881878 -0.447033 -0.19905 0.87209 -0.447033 -0.261892 0.828089 -0.495662 -0.388118 0.805931 -0.447033 -0.410569 0.794729 -0.447033 -0.454483 0.770459 -0.447033 -0.498338 0.711322 -0.495662 -0.594589 0.633074 -0.495662 -0.699363 0.557721 -0.447033 -0.743766 0.496965 -0.447033 -0.782903 0.432693 -0.447033 -0.78741 0.366475 -0.495662 -0.826427 0.342314 -0.447033 -0.822986 0.277512 -0.495662 -0.832187 0.248564 -0.495662 -0.866165 0.223426 -0.447033 -0.852788 0.164536 -0.495662 -0.857549 0.137585 -0.495662 -0.861367 0.111207 -0.495662 -0.864305 0.0854207 -0.495662 -0.866424 0.060241 -0.495662 -0.867782 0.0356773 -0.495662 -0.868436 0.0117362 -0.495662 -0.868436 -0.011736 -0.495662 -0.867782 -0.0356775 -0.495662 -0.866424 -0.0602411 -0.495662 -0.864305 -0.0854208 -0.495662 -0.861367 -0.111207 -0.495662 -0.857549 -0.137585 -0.495662 -0.852788 -0.164536 -0.495662 -0.832187 -0.248564 -0.495662 -0.822986 -0.277512 -0.495662 -0.826425 -0.342319 -0.447033 -0.78741 -0.366475 -0.495662 -0.757408 -0.475915 -0.447033 -0.69936 -0.557725 -0.447033 -0.649711 -0.576364 -0.495662 -0.564297 -0.660218 -0.495662 -0.462751 -0.73497 -0.495662 -0.342316 -0.826427 -0.447033 -0.295439 -0.84432 -0.447033 -0.217956 -0.840723 -0.495662 -6.66203e-08 -0.894517 -0.447033 0.0250895 -0.894165 -0.447033 0.0751854 -0.891352 -0.447033 0.125047 -0.885734 -0.447033 0.174512 -0.877329 -0.447033 0.240048 -0.834683 -0.495662 0.432695 -0.782902 -0.447033 0.480756 -0.723321 -0.495662 0.577119 -0.683444 -0.447033 0.650011 -0.614529 -0.447033 0.662355 -0.561787 -0.495662 0.728886 -0.472275 -0.495662 0.805933 -0.388114 -0.447033 0.806758 -0.321653 -0.495662 0.844321 -0.295438 -0.447033 0.836328 -0.234254 -0.495662 0.843735 -0.205985 -0.495662 0.850034 -0.17822 -0.495662 0.85529 -0.15099 -0.495662 0.859571 -0.124323 -0.495662 0.862942 -0.0982386 -0.495662 0.888893 -0.100153 -0.447033 0.891352 0.0751875 -0.447033 0.885733 0.12505 -0.447033 0.881878 0.149842 -0.447033 0.877329 0.174513 -0.447033 0.872089 0.199052 -0.447033 0.866163 0.223434 -0.447033 0.859556 0.247638 -0.447033 0.852274 0.271645 -0.447033 0.8357 0.319008 -0.447033 0.826425 0.342319 -0.447033 0.8165 0.365361 -0.447033 0.794728 0.41057 -0.447033 0.770458 0.454483 -0.447033 0.757408 0.475915 -0.447033 0.743762 0.496969 -0.447033 0.729533 0.517632 -0.447033 0.683443 0.577119 -0.447033 0.66699 0.596059 -0.447033 0.632517 0.632521 -0.447033 0.61453 0.650011 -0.447033 0.596058 0.66699 -0.447033 0.537888 0.714729 -0.447033 0.496965 0.743765 -0.447033 0.47591 0.75741 -0.447033 0.454482 0.770459 -0.447033 0.342316 0.826427 -0.447033 0.29544 0.84432 -0.447033 0.247633 0.859558 -0.447033 0.223428 0.866165 -0.447033 0.199048 0.87209 -0.447033 -0.0250893 0.894165 -0.447033 -0.0751856 0.891352 -0.447033 -0.125047 0.885734 -0.447033 -0.174512 0.877329 -0.447033 -0.223431 0.866164 -0.447033 -0.247636 0.859557 -0.447033 -0.271645 0.852274 -0.447033 -0.432696 0.782902 -0.447033 -0.475913 0.757408 -0.447033 -0.496969 0.743763 -0.447033 -0.517632 0.729533 -0.447033 -0.577119 0.683443 -0.447033 -0.596059 0.66699 -0.447033 -0.614532 0.650009 -0.447033 -0.66699 0.596058 -0.447033 -0.683446 0.577116 -0.447033 -0.714729 0.537888 -0.447033 -0.729534 0.51763 -0.447033 -0.757411 0.47591 -0.447033 -0.770459 0.454482 -0.447033 -0.794731 0.410564 -0.447033 -0.805933 0.388114 -0.447033 -0.8165 0.365361 -0.447033 -0.835703 0.319001 -0.447033 -0.844321 0.295438 -0.447033 -0.852274 0.271643 -0.447033 -0.859558 0.247631 -0.447033 -0.87209 0.199047 -0.447033 -0.87733 0.174509 -0.447033 -0.881879 0.149833 -0.447033 -0.885735 0.125041 -0.447033 -0.888893 0.100154 -0.447033 -0.891352 0.0751808 -0.447033 -0.89311 0.0501503 -0.447033 -0.894166 0.0250842 -0.447033 -0.894517 8.14756e-08 -0.447033 -0.894165 -0.0250844 -0.447033 -0.89311 -0.0501622 -0.447033 -0.891352 -0.0751876 -0.447033 -0.888892 -0.100156 -0.447033 -0.885733 -0.12505 -0.447033 -0.881878 -0.149842 -0.447033 -0.877329 -0.174513 -0.447033 -0.872089 -0.199052 -0.447033 -0.859556 -0.247638 -0.447033 -0.852274 -0.271645 -0.447033 -0.844319 -0.295444 -0.447033 -0.8357 -0.319008 -0.447033 -0.8165 -0.365361 -0.447033 -0.805931 -0.38812 -0.447033 -0.794728 -0.41057 -0.447033 -0.770458 -0.454483 -0.447033 -0.743762 -0.496969 -0.447033 -0.729533 -0.517632 -0.447033 -0.714728 -0.53789 -0.447033 -0.683443 -0.577119 -0.447033 -0.666989 -0.596059 -0.447033 -0.614529 -0.650011 -0.447033 -0.596058 -0.66699 -0.447033 -0.577116 -0.683446 -0.447033 -0.517631 -0.729534 -0.447033 -0.496965 -0.743765 -0.447033 -0.475911 -0.75741 -0.447033 -0.365361 -0.8165 -0.447033 -0.319003 -0.835702 -0.447033 -0.271644 -0.852274 -0.447033 -0.247633 -0.859558 -0.447033 -0.223428 -0.866165 -0.447033 0.0501577 -0.89311 -0.447033 0.100155 -0.888893 -0.447033 0.149839 -0.881878 -0.447033 0.19905 -0.87209 -0.447033 0.223431 -0.866164 -0.447033 0.247635 -0.859557 -0.447033 0.410569 -0.794729 -0.447033 0.454483 -0.770459 -0.447033 0.475914 -0.757408 -0.447033 0.496969 -0.743763 -0.447033 0.557724 -0.69936 -0.447033 0.596059 -0.66699 -0.447033 0.614532 -0.650009 -0.447033 0.632521 -0.632518 -0.447033 0.66699 -0.596058 -0.447033 0.683446 -0.577116 -0.447033 0.729534 -0.517631 -0.447033 0.743765 -0.496965 -0.447033 0.757411 -0.47591 -0.447033 0.770459 -0.454482 -0.447033 0.794731 -0.410564 -0.447033 0.8165 -0.365361 -0.447033 0.826427 -0.342314 -0.447033 0.835703 -0.319001 -0.447033 0.852274 -0.271643 -0.447033 0.859558 -0.24763 -0.447033 0.866165 -0.223426 -0.447033 0.87209 -0.199047 -0.447033 0.87733 -0.174509 -0.447033 0.881879 -0.149832 -0.447033 0.885735 -0.125041 -0.447033 0.891352 -0.0751809 -0.447033 0.89311 -0.0501506 -0.447033 0.894166 -0.0250843 -0.447033 -0.998427 0.0560703 0 -0.999607 0.0280461 0 -0.998427 0.0560708 0 -1 -1.74846e-07 -0 -0.999607 0.0280466 0 -1 3.01992e-07 0 -0.993712 0.111964 0 -0.990181 0.13979 0 -0.990181 0.13979 0 -0.993712 0.111965 0 -0.996462 0.0840504 0 -0.996462 0.0840504 0 -0.974928 0.222521 0 -0.980785 0.19509 0 -0.974928 0.222521 0 -0.980785 0.19509 0 -0.985871 0.167506 0 -0.985871 0.167506 0 -0.952775 0.303677 0 -0.952775 0.303677 0 -0.960917 0.276835 0 -0.968304 0.249776 0 -0.960917 0.276835 0 -0.968304 0.249776 0 -0.934249 0.356622 0 -0.92388 0.382683 0 -0.92388 0.382683 0 -0.943883 0.330279 0 -0.943883 0.330279 0 -0.934249 0.356622 0 -0.888446 0.458982 0 -0.900969 0.433884 0 -0.888446 0.458982 0 -0.900969 0.433884 0 -0.912783 0.408444 0 -0.912783 0.408444 0 -0.846724 0.532032 0 -0.846724 0.532032 0 -0.861313 0.508075 0 -0.875223 0.483719 0 -0.861313 0.508075 0 -0.875223 0.483719 0 -0.815561 0.578671 0 -0.79901 0.601317 0 -0.79901 0.601317 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.815561 0.578671 0 -0.745642 0.666347 0 -0.764037 0.645172 0 -0.745642 0.666346 0 -0.764037 0.645172 0 -0.781831 0.62349 0 -0.781831 0.62349 0 -0.686997 0.72666 0 -0.686997 0.72666 0 -0.707107 0.707107 0 -0.72666 0.686997 0 -0.707107 0.707107 0 -0.72666 0.686997 0 -0.645172 0.764037 0 -0.62349 0.781831 0 -0.62349 0.781832 0 -0.666346 0.745642 0 -0.666346 0.745642 0 -0.645172 0.764037 0 -0.55557 0.831469 0 -0.578671 0.815561 0 -0.55557 0.83147 0 -0.578672 0.815561 0 -0.601317 0.799011 0 -0.601317 0.79901 0 -0.483719 0.875224 0 -0.483719 0.875223 0 -0.508075 0.861313 0 -0.532032 0.846724 0 -0.508075 0.861313 0 -0.532032 0.846724 0 -0.433884 0.900969 0 -0.408444 0.912783 0 -0.408444 0.912783 0 -0.458982 0.888446 0 -0.458982 0.888446 0 -0.433883 0.900969 0 -0.330279 0.943883 0 -0.356622 0.934249 0 -0.330279 0.943883 0 -0.356621 0.934249 0 -0.382684 0.923879 0 -0.382684 0.923879 0 -0.249777 0.968304 0 -0.249777 0.968304 0 -0.276836 0.960917 0 -0.303677 0.952775 0 -0.276835 0.960917 0 -0.303677 0.952775 0 -0.19509 0.980785 0 -0.167506 0.985871 0 -0.167506 0.985871 0 -0.222521 0.974928 0 -0.222521 0.974928 0 -0.19509 0.980785 0 -0.0840506 0.996462 0 -0.111965 0.993712 0 -0.0840506 0.996462 0 -0.111965 0.993712 0 -0.13979 0.990181 0 -0.13979 0.990181 0 -1.19249e-08 1 0 -1.19249e-08 1 0 -0.0280463 0.999607 0 -0.0560705 0.998427 0 -0.0280463 0.999607 0 -0.0560705 0.998427 0 0.0560705 0.998427 0 0.0840505 0.996462 0 0.0840505 0.996462 0 0.0280463 0.999607 0 0.0280463 0.999607 0 0.0560705 0.998427 0 0.167506 0.985871 0 0.13979 0.990181 0 0.167506 0.985871 0 0.13979 0.990181 0 0.111965 0.993712 0 0.111965 0.993712 0 0.249777 0.968304 0 0.249777 0.968304 0 0.222521 0.974928 0 0.19509 0.980785 0 0.222521 0.974928 0 0.19509 0.980785 0 0.303677 0.952775 0 0.330279 0.943883 0 0.330279 0.943883 0 0.276836 0.960917 0 0.276836 0.960917 0 0.303677 0.952775 0 0.408444 0.912783 0 0.382684 0.92388 0 0.408444 0.912783 0 0.382683 0.92388 0 0.356622 0.934249 0 0.356622 0.934249 0 0.483719 0.875224 0 0.483719 0.875223 0 0.458982 0.888446 0 0.433884 0.900969 0 0.458982 0.888446 0 0.433884 0.900969 0 0.532032 0.846724 0 0.55557 0.831469 0 0.55557 0.83147 0 0.508076 0.861313 0 0.508075 0.861313 0 0.532032 0.846724 0 0.62349 0.781832 0 0.601317 0.79901 0 0.62349 0.781831 0 0.601317 0.799011 0 0.578672 0.815561 0 0.578671 0.815561 0 0.686997 0.72666 0 0.686997 0.72666 0 0.666346 0.745642 0 0.645172 0.764037 0 0.666347 0.745642 0 0.645172 0.764037 0 0.72666 0.686997 0 0.745642 0.666346 0 0.745642 0.666346 0 0.707107 0.707107 0 0.707107 0.707107 0 0.72666 0.686997 0 0.799011 0.601317 0 0.781831 0.62349 0 0.79901 0.601317 0 0.781832 0.62349 0 0.764037 0.645172 0 0.764037 0.645172 0 0.846724 0.532032 0 0.846724 0.532032 0 0.83147 0.55557 0 0.815561 0.578671 0 0.83147 0.55557 0 0.815561 0.578671 0 0.875223 0.483719 0 0.888446 0.458982 0 0.888446 0.458982 0 0.861313 0.508075 0 0.861313 0.508075 0 0.875223 0.483719 0 0.923879 0.382684 0 0.912783 0.408444 0 0.92388 0.382683 0 0.912783 0.408444 0 0.900969 0.433884 0 0.900969 0.433884 0 0.952775 0.303677 0 0.952775 0.303677 0 0.943883 0.330279 0 0.934249 0.356622 0 0.943883 0.330279 0 0.934249 0.356622 0 0.968304 0.249777 0 0.974928 0.222521 0 0.974928 0.222521 0 0.960917 0.276835 0 0.960917 0.276835 0 0.968304 0.249776 0 0.990181 0.13979 0 0.985871 0.167506 0 0.990181 0.13979 0 0.985871 0.167506 0 0.980785 0.19509 0 0.980785 0.19509 0 0.998427 0.0560706 0 0.998427 0.0560703 0 0.996462 0.0840506 0 0.993712 0.111964 0 0.996462 0.0840504 0 0.993712 0.111965 0 1 8.74228e-08 0 0.999607 -0.0280464 0 0.999607 -0.0280462 0 0.999607 0.0280464 0 0.999607 0.0280461 0 1 8.74228e-08 0 0.993712 -0.111964 0 0.996462 -0.0840505 0 0.993712 -0.111964 0 0.996461 -0.0840507 0 0.998427 -0.0560704 0 0.998427 -0.0560704 0 0.980785 -0.19509 0 0.980785 -0.19509 0 0.985871 -0.167506 0 0.990181 -0.13979 0 0.985871 -0.167506 0 0.990181 -0.13979 0 0.968304 -0.249776 0 0.960917 -0.276836 0 0.960917 -0.276836 0 0.974928 -0.222521 0 0.974928 -0.222521 0 0.968304 -0.249776 0 0.934249 -0.356622 0 0.943883 -0.330279 0 0.934249 -0.356621 0 0.943883 -0.330279 0 0.952775 -0.303677 0 0.952775 -0.303677 0 0.900969 -0.433884 0 0.900969 -0.433884 0 0.912783 -0.408444 0 0.92388 -0.382683 0 0.912783 -0.408444 0 0.92388 -0.382683 0 0.875223 -0.483719 0 0.861313 -0.508075 0 0.861313 -0.508075 0 0.888446 -0.458982 0 0.888446 -0.458982 0 0.875223 -0.483719 0 0.815561 -0.578671 0 0.83147 -0.55557 0 0.815561 -0.578671 0 0.83147 -0.55557 0 0.846724 -0.532032 0 0.846724 -0.532032 0 0.764037 -0.645172 0 0.764037 -0.645172 0 0.781832 -0.62349 0 0.799011 -0.601317 0 0.781831 -0.62349 0 0.799011 -0.601317 0 0.72666 -0.686997 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.745642 -0.666347 0 0.745642 -0.666347 0 0.72666 -0.686997 0 0.645172 -0.764037 0 0.666347 -0.745642 0 0.645172 -0.764037 0 0.666347 -0.745642 0 0.686997 -0.72666 0 0.686997 -0.72666 0 0.578671 -0.815561 0 0.578671 -0.815561 0 0.601317 -0.799011 0 0.62349 -0.781832 0 0.601317 -0.799011 0 0.62349 -0.781832 0 0.532032 -0.846724 0 0.508075 -0.861313 0 0.508075 -0.861313 0 0.55557 -0.83147 0 0.55557 -0.83147 0 0.532032 -0.846724 0 0.433884 -0.900969 0 0.458982 -0.888446 0 0.433884 -0.900969 0 0.458982 -0.888446 0 0.483719 -0.875223 0 0.483719 -0.875223 0 0.356622 -0.934249 0 0.356622 -0.934249 0 0.382683 -0.92388 0 0.408444 -0.912783 0 0.382683 -0.92388 0 0.408444 -0.912783 0 0.303677 -0.952775 0 0.276836 -0.960917 0 0.276836 -0.960917 0 0.330279 -0.943883 0 0.330279 -0.943883 0 0.303677 -0.952775 0 0.19509 -0.980785 0 0.222521 -0.974928 0 0.19509 -0.980785 0 0.222521 -0.974928 0 0.249776 -0.968304 0 0.249776 -0.968304 0 0.111964 -0.993712 0 0.111964 -0.993712 0 0.13979 -0.990181 0 0.167506 -0.985871 0 0.13979 -0.990181 0 0.167506 -0.985871 0 0.0560704 -0.998427 0 0.0280463 -0.999607 0 0.0280463 -0.999607 0 0.0840505 -0.996462 0 0.0840506 -0.996462 0 0.0560704 -0.998427 0 4.37114e-08 -1 0 -0.0280462 -0.999607 -0 -0.0280462 -0.999607 -0 -7.54979e-08 -1 -0 -0.0560704 -0.998427 -0 -0.0560704 -0.998427 -0 -0.0840505 -0.996462 -0 -0.0840505 -0.996462 -0 -0.111964 -0.993712 -0 -0.111964 -0.993712 -0 -0.13979 -0.990181 -0 -0.13979 -0.990181 -0 -0.167506 -0.985871 -0 -0.167506 -0.985871 -0 -0.19509 -0.980785 -0 -0.19509 -0.980785 -0 -0.222521 -0.974928 -0 -0.222521 -0.974928 -0 -0.249777 -0.968304 -0 -0.249776 -0.968304 -0 -0.276835 -0.960917 -0 -0.276835 -0.960917 -0 -0.303677 -0.952775 -0 -0.303677 -0.952775 -0 -0.330279 -0.943883 -0 -0.330279 -0.943883 -0 -0.356622 -0.934249 -0 -0.356622 -0.934249 -0 -0.382683 -0.92388 -0 -0.382683 -0.92388 -0 -0.408444 -0.912783 -0 -0.408444 -0.912783 -0 -0.433884 -0.900969 -0 -0.433884 -0.900969 -0 -0.458982 -0.888446 -0 -0.458982 -0.888446 -0 -0.483719 -0.875223 -0 -0.483719 -0.875223 -0 -0.508075 -0.861313 -0 -0.508075 -0.861313 -0 -0.532032 -0.846724 -0 -0.532032 -0.846724 -0 -0.55557 -0.83147 -0 -0.55557 -0.83147 -0 -0.578671 -0.815561 -0 -0.578671 -0.815561 -0 -0.601317 -0.799011 -0 -0.601317 -0.79901 -0 -0.62349 -0.781832 -0 -0.62349 -0.781832 -0 -0.645172 -0.764037 -0 -0.645172 -0.764037 -0 -0.666347 -0.745642 -0 -0.666347 -0.745642 -0 -0.686997 -0.72666 -0 -0.686997 -0.72666 -0 -0.707107 -0.707107 -0 -0.707107 -0.707107 -0 -0.72666 -0.686997 -0 -0.72666 -0.686997 -0 -0.745642 -0.666347 -0 -0.745642 -0.666347 -0 -0.764037 -0.645172 -0 -0.764037 -0.645172 -0 -0.781831 -0.62349 -0 -0.781831 -0.62349 -0 -0.799011 -0.601317 -0 -0.79901 -0.601317 -0 -0.815561 -0.578671 -0 -0.815561 -0.578671 -0 -0.83147 -0.55557 -0 -0.83147 -0.55557 -0 -0.846724 -0.532032 -0 -0.846724 -0.532032 -0 -0.861313 -0.508075 -0 -0.861313 -0.508075 -0 -0.875223 -0.483719 -0 -0.875223 -0.483719 -0 -0.888446 -0.458982 -0 -0.888446 -0.458982 -0 -0.900969 -0.433884 -0 -0.900969 -0.433884 -0 -0.912783 -0.408444 -0 -0.912783 -0.408444 -0 -0.92388 -0.382683 -0 -0.92388 -0.382683 -0 -0.934249 -0.356622 -0 -0.934249 -0.356622 -0 -0.943883 -0.330279 -0 -0.943883 -0.330279 -0 -0.952775 -0.303677 -0 -0.952775 -0.303677 -0 -0.960917 -0.276836 -0 -0.960917 -0.276836 -0 -0.968304 -0.249776 -0 -0.968304 -0.249776 -0 -0.974928 -0.222521 -0 -0.974928 -0.222521 -0 -0.980785 -0.19509 -0 -0.980785 -0.19509 -0 -0.985871 -0.167506 -0 -0.985871 -0.167506 -0 -0.990181 -0.13979 -0 -0.990181 -0.13979 -0 -0.993712 -0.111964 -0 -0.993712 -0.111964 -0 -0.996462 -0.0840505 -0 -0.996462 -0.0840505 -0 -0.998427 -0.0560704 -0 -0.998427 -0.0560705 -0 -0.999607 -0.0280463 -0 -0.999607 -0.0280463 -0 - - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 8 7 3 5 13 14 15 16 8 12 17 18 3 19 20 21 22 3 13 19 23 18 24 25 26 27 4 28 5 24 29 23 29 25 23 30 31 32 33 34 35 36 33 37 38 39 40 37 33 35 34 25 27 35 34 27 25 29 26 41 36 42 33 36 41 39 42 40 41 42 39 43 39 38 31 30 43 44 45 30 31 43 38 44 30 32 46 17 45 45 17 12 45 44 46 47 7 6 48 49 50 18 19 24 51 52 53 54 55 56 52 57 58 59 60 61 62 63 58 64 65 66 67 68 69 65 70 71 72 73 74 75 76 74 77 78 79 80 81 82 79 83 73 61 76 84 85 86 62 59 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 103 106 107 108 109 110 105 101 111 112 113 114 115 116 117 118 119 120 121 122 116 123 124 125 126 127 117 128 129 130 131 124 132 133 119 134 112 135 136 137 135 132 138 139 140 141 142 143 144 145 146 147 136 148 149 142 150 151 152 153 143 152 142 154 155 156 157 158 159 160 161 159 145 162 163 164 165 163 166 167 168 169 170 166 162 171 172 173 174 175 170 176 173 177 178 179 171 180 181 182 183 184 185 178 186 187 188 189 47 190 191 192 193 194 195 196 194 197 198 199 200 201 202 191 203 204 205 206 195 207 208 209 210 203 210 211 212 213 214 212 215 216 217 184 201 218 219 220 221 222 223 224 225 222 222 225 226 227 225 228 229 230 231 7 47 189 232 28 4 233 232 234 188 235 189 234 236 233 233 28 232 235 49 48 58 85 62 48 189 235 237 236 234 238 237 234 238 239 237 240 239 241 55 48 50 239 238 241 55 50 56 242 243 53 55 54 242 243 242 54 244 240 245 241 245 240 246 247 244 244 245 246 243 248 53 249 247 250 248 251 53 247 246 250 252 253 254 255 53 251 256 64 77 255 257 51 246 245 258 259 255 251 260 249 261 262 255 259 261 263 260 260 263 264 262 265 255 263 266 264 257 265 267 268 265 269 262 269 265 270 265 268 266 263 271 272 270 268 271 273 274 275 270 272 276 274 277 278 270 275 279 280 278 281 278 282 278 275 282 278 281 283 279 283 284 283 285 286 281 285 283 286 287 283 287 288 284 289 290 287 289 287 286 291 287 290 292 288 291 293 294 291 291 290 293 294 293 295 292 294 296 297 294 298 295 298 294 298 299 297 297 300 296 301 297 299 300 302 303 297 301 302 304 305 302 304 302 301 306 307 303 305 306 302 308 306 309 306 305 309 310 307 311 311 306 308 308 312 311 313 311 312 314 315 313 311 313 315 316 317 310 315 314 318 319 318 320 318 319 315 321 322 323 320 324 319 324 325 322 322 319 324 326 327 323 328 322 325 329 326 328 322 328 326 330 327 331 331 326 329 331 332 333 329 332 331 330 334 335 331 333 334 336 337 334 336 334 333 338 337 339 337 338 334 340 338 341 339 341 338 342 0 340 343 344 335 0 342 345 340 341 342 1 0 345 346 347 0 346 2 348 2 1 349 350 2 349 351 2 350 350 352 351 352 353 351 354 348 355 353 352 356 357 353 356 358 353 357 358 359 360 357 361 358 362 358 361 362 361 363 364 362 363 365 362 364 365 366 367 364 368 365 369 365 368 369 368 370 369 371 372 371 369 370 366 373 374 371 375 372 376 372 375 376 375 377 376 378 379 378 376 377 380 381 382 378 383 379 384 379 383 384 383 385 385 386 384 387 386 385 386 388 389 387 390 386 391 386 390 391 390 392 392 393 391 394 393 392 395 396 394 393 394 396 397 396 398 399 396 395 395 400 399 401 399 400 399 401 402 401 403 402 404 402 403 404 403 405 406 405 407 405 406 404 408 409 407 406 407 409 408 410 411 411 409 408 412 413 414 410 415 411 415 410 416 415 416 417 418 417 416 419 417 418 418 420 419 420 421 419 421 420 15 421 15 14 422 14 16 423 424 425 426 422 16 427 428 429 425 424 430 431 432 433 427 434 428 435 436 437 438 439 440 441 442 443 436 444 443 445 446 447 448 449 450 451 452 453 445 454 452 455 456 457 458 459 460 461 462 463 464 463 465 466 467 468 462 469 470 471 472 473 474 473 475 476 477 478 479 480 478 481 482 483 484 485 486 487 488 489 488 483 490 491 492 493 494 495 493 496 497 498 496 499 492 500 501 502 501 503 504 505 506 507 508 509 500 510 511 512 513 512 506 514 515 516 511 517 516 518 519 520 519 521 522 523 524 525 518 520 526 527 528 529 530 528 523 531 532 533 532 11 534 535 536 537 538 9 532 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 547 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 570 527 571 572 573 574 569 575 574 576 577 578 573 572 578 579 580 581 577 576 581 582 583 584 583 580 579 582 585 586 586 583 582 587 588 585 589 590 588 589 591 592 593 589 588 592 594 595 596 597 598 599 595 600 594 601 595 602 603 600 601 600 595 604 605 606 603 607 608 609 610 611 610 609 608 612 613 614 610 613 611 615 612 616 617 618 619 615 616 620 615 620 621 622 623 624 625 621 620 626 627 628 627 621 625 628 629 626 626 630 627 631 632 633 629 631 626 634 633 632 635 636 637 634 638 639 639 633 634 639 638 640 641 642 643 644 645 640 639 640 645 644 277 646 644 646 645 277 647 646 648 646 647 632 631 629 616 612 614 625 628 627 608 609 603 613 612 611 602 600 601 603 602 607 592 591 649 594 592 649 587 593 588 589 593 591 650 651 652 586 585 588 581 580 577 579 584 583 573 578 577 653 580 654 655 656 573 573 569 574 570 571 568 568 575 569 657 563 658 657 9 564 659 660 661 662 543 660 663 664 665 666 556 667 668 665 669 670 667 671 672 673 674 675 665 676 677 678 679 678 674 552 675 553 669 545 680 677 681 549 682 683 684 681 671 685 664 686 687 683 688 689 690 548 691 692 693 694 695 696 691 697 567 698 557 699 700 701 702 693 696 703 693 704 661 705 698 704 706 707 659 698 708 709 710 707 711 712 709 713 714 542 715 716 717 712 718 719 717 720 721 722 723 724 725 726 727 728 725 729 730 731 732 733 734 735 736 737 738 737 739 740 741 742 743 736 744 743 745 746 747 741 748 742 749 750 751 752 746 753 754 755 756 757 758 759 760 523 518 761 740 733 223 756 759 720 726 762 537 713 544 763 718 715 764 765 544 507 509 505 658 766 767 766 563 535 533 534 570 524 527 534 527 529 571 760 530 523 523 528 527 525 521 518 526 760 518 768 769 487 519 515 770 519 770 520 515 511 516 515 514 770 771 772 773 511 510 517 774 515 522 512 507 506 510 512 513 775 507 773 500 509 507 500 775 503 500 502 508 776 777 501 501 777 502 498 776 501 498 504 778 776 498 497 492 499 493 496 498 499 778 494 499 487 769 493 769 491 493 489 768 487 488 779 489 487 495 780 488 780 781 779 488 490 471 473 474 483 486 481 490 483 482 485 481 486 782 783 784 484 477 476 477 484 486 784 785 477 479 472 480 477 479 478 473 472 479 786 479 785 473 786 787 788 469 789 474 475 790 790 468 467 468 790 475 468 462 466 791 466 462 463 792 461 791 462 461 451 793 794 464 792 463 795 463 470 796 456 455 464 465 796 456 796 465 457 797 798 456 799 800 798 797 793 456 797 457 793 797 794 801 802 803 451 794 452 452 454 453 804 447 446 445 447 454 448 804 446 449 448 446 805 449 806 807 450 449 449 442 807 808 809 443 441 807 442 435 444 436 443 444 441 439 438 810 810 437 436 439 431 440 437 810 438 431 433 440 811 431 812 813 432 431 813 814 432 814 813 434 427 814 434 815 429 428 816 422 426 429 815 817 815 430 817 424 423 818 430 815 425 816 818 423 818 816 426 819 820 648 821 822 823 646 648 820 819 824 820 820 825 645 826 827 633 826 639 825 827 828 631 633 639 826 829 830 831 631 633 827 623 621 627 631 828 626 622 615 621 828 630 626 612 832 617 623 627 630 617 833 611 623 622 621 609 833 605 832 615 622 605 834 603 612 615 832 835 836 837 612 617 611 597 592 595 611 833 609 589 592 596 609 605 603 838 839 840 834 600 603 586 588 650 600 834 599 652 654 583 597 595 599 841 842 843 592 597 596 653 655 577 589 596 590 844 845 655 588 590 650 656 533 569 650 652 586 11 846 524 583 586 652 846 847 525 583 654 580 847 848 521 580 653 577 848 849 522 573 577 655 850 851 771 573 656 569 852 511 774 569 533 570 773 512 852 534 527 570 775 772 853 523 527 524 853 854 503 518 523 525 854 855 504 519 518 521 855 856 778 515 519 522 856 857 494 511 515 774 857 858 495 512 511 852 858 859 780 507 512 773 860 861 782 500 507 775 862 483 781 500 503 501 784 486 862 498 501 504 783 863 785 499 498 778 863 864 786 493 499 494 787 864 865 487 493 495 787 866 475 488 487 780 866 469 468 781 483 488 470 788 867 862 486 483 868 869 870 784 477 486 795 799 465 785 479 477 800 868 871 786 473 479 800 872 797 787 475 473 458 794 872 475 866 468 458 873 452 469 462 468 801 445 873 462 470 463 801 806 446 465 463 795 805 874 875 465 799 456 805 808 442 797 456 800 876 877 878 794 797 872 879 436 809 452 794 458 879 880 810 873 445 452 880 812 439 801 446 445 811 881 882 806 449 446 883 813 811 805 442 449 883 884 434 808 443 442 884 885 428 443 809 436 885 886 815 436 879 810 886 887 425 810 880 439 887 888 423 431 439 812 888 889 816 813 431 811 889 890 422 434 813 883 890 891 14 428 434 884 891 892 421 815 428 885 892 893 419 425 815 886 893 894 417 423 425 887 894 895 415 816 423 888 895 896 411 816 889 422 414 409 896 422 890 14 897 406 414 14 891 421 898 404 897 421 892 419 898 899 402 419 893 417 899 398 399 417 894 415 397 900 901 415 895 411 902 393 397 411 896 409 902 388 391 409 414 406 389 903 904 897 404 406 389 905 384 898 402 404 905 906 379 399 402 899 380 376 906 398 396 399 380 907 372 393 396 397 366 369 907 391 393 902 908 909 910 391 388 386 367 359 362 384 386 389 360 908 911 384 905 379 360 912 353 379 906 376 912 348 351 376 380 372 346 354 913 372 907 369 347 913 914 366 365 369 347 915 340 367 362 365 335 338 915 359 358 362 344 916 330 360 353 358 916 917 327 912 351 353 917 918 323 2 351 348 919 920 316 0 2 346 921 319 321 340 0 347 310 315 921 915 338 340 307 317 922 334 338 335 922 923 303 331 334 330 923 924 300 326 331 327 924 925 296 322 326 323 925 926 292 319 322 321 926 927 288 315 319 921 927 928 284 311 315 310 928 929 279 306 311 307 930 931 932 306 303 302 267 270 280 297 302 300 932 933 257 294 297 296 933 57 51 292 291 294 242 52 63 291 288 287 55 63 934 283 287 284 48 934 935 279 278 283 936 189 935 280 270 278 937 7 936 267 265 270 12 937 938 257 255 265 52 58 63 255 51 53 45 939 30 52 242 53 30 940 43 55 242 63 941 39 43 48 55 934 942 41 39 935 189 48 943 33 41 936 7 189 944 34 33 7 937 12 940 945 946 45 938 939 947 25 948 940 30 939 949 23 947 941 43 940 950 18 949 942 39 941 951 3 950 942 943 41 4 951 952 943 944 33 949 947 953 34 948 25 954 234 232 25 947 23 955 238 234 18 23 949 956 241 238 3 18 950 957 245 241 4 3 951 958 955 959 954 232 952 960 246 258 954 955 234 961 250 960 955 956 238 962 261 961 956 957 241 961 960 963 964 271 263 250 261 249 250 246 960 965 274 273 261 250 961 266 271 276 962 964 263 274 648 647 277 274 647 276 271 274 646 820 645 966 824 819 966 641 824 645 825 639 824 967 825 827 968 636 968 826 967 636 969 828 827 826 968 623 630 970 828 827 636 971 972 973 828 969 630 832 622 974 969 970 630 975 976 977 970 624 623 833 619 606 624 974 622 978 979 980 618 832 974 604 835 834 832 618 617 981 597 599 833 617 619 982 983 984 833 606 605 590 596 839 604 834 605 650 590 838 835 599 834 985 986 987 981 599 835 654 988 841 597 981 598 653 841 844 596 598 839 989 990 991 590 839 838 845 531 656 650 838 651 992 538 531 651 988 652 846 10 993 654 652 988 993 994 847 653 654 841 994 995 848 844 655 653 996 997 850 655 845 656 998 774 849 656 531 533 771 852 998 532 534 533 772 851 999 11 524 534 853 999 1000 525 524 846 854 1000 1001 521 525 847 1001 1002 855 522 521 848 1002 1003 856 774 522 849 1003 1004 857 852 774 998 1004 1005 858 773 852 771 1006 1007 860 775 773 772 1008 781 859 503 775 853 782 862 1008 504 503 854 783 861 1009 778 504 855 863 1009 1010 494 778 856 1010 1011 864 495 494 857 1012 1013 1014 780 495 858 789 866 865 859 781 780 788 1014 1015 1008 862 781 1015 1016 867 782 784 862 1017 795 867 783 785 784 868 799 1017 863 786 785 870 1018 871 864 787 786 459 872 871 787 865 866 460 1019 1020 866 789 469 802 873 460 469 788 470 803 1021 1022 470 867 795 874 806 803 799 795 1017 875 1023 1024 799 868 800 1025 808 875 872 800 871 1026 809 1025 458 872 459 876 879 1026 873 458 460 1027 880 876 802 801 873 881 812 1027 803 806 801 1028 1029 1030 874 805 806 1031 883 882 875 808 805 1032 884 1031 1025 809 808 1033 885 1032 809 1026 879 1034 886 1033 879 876 880 1035 887 1034 880 1027 812 1036 888 1035 811 812 881 1037 889 1036 883 811 882 1038 890 1037 884 883 1031 1039 891 1038 885 884 1032 1040 892 1039 886 885 1033 1041 893 1040 887 886 1034 1042 894 1041 888 887 1035 1043 895 1042 889 888 1036 1043 412 896 890 889 1037 1044 1045 1046 890 1038 891 1047 897 413 891 1039 892 1048 898 1047 892 1040 893 1049 899 1048 893 1041 894 900 398 1049 894 1042 895 1050 1051 1052 895 1043 896 1053 902 901 896 412 414 903 388 1053 414 413 897 1054 1055 1056 1047 898 897 1057 905 904 1048 899 898 381 906 1057 1049 398 899 382 1058 1059 900 397 398 373 907 382 901 902 397 374 1060 1061 388 902 1053 1062 367 374 388 903 389 908 359 1062 905 389 904 910 1063 911 905 1057 906 355 912 911 380 906 381 354 1064 1065 380 382 907 1065 1066 913 907 373 366 1067 1068 1069 374 367 366 343 915 914 367 1062 359 344 1069 1070 908 360 359 1070 1071 916 911 912 360 1071 1072 917 355 348 912 1072 1073 918 346 348 354 1074 321 918 347 346 913 316 921 1074 914 915 347 317 920 1075 343 335 915 922 1075 1076 330 335 344 923 1076 1077 327 330 916 1077 1078 924 323 327 917 1078 1079 925 321 323 918 1079 1080 926 921 321 1074 1080 1081 927 310 921 316 1081 1082 928 307 310 317 1083 1084 930 303 307 922 1085 280 929 303 923 300 932 267 1085 296 300 924 933 931 1086 292 296 925 1086 1087 57 288 292 926 1087 85 58 284 288 927 1088 934 62 284 928 279 935 1088 1089 280 279 929 936 1089 1090 1085 267 280 1091 937 1090 267 932 257 1092 938 1091 933 51 257 1093 1094 1095 57 52 51 939 945 940 946 941 940 45 12 938 62 934 63 941 1096 942 1088 935 934 942 1097 943 936 935 1089 1098 944 943 1090 937 936 944 1099 948 1091 938 937 21 946 1100 939 1092 945 953 947 1101 949 953 1102 948 34 944 1096 941 946 950 1102 1103 1097 942 1096 1104 951 1103 1098 943 1097 1105 952 1104 1098 1099 944 1106 1102 953 948 1101 947 954 959 955 958 956 955 952 232 4 949 1102 950 956 1107 957 951 950 1103 957 1108 258 952 951 1104 1109 958 1110 959 954 1105 963 960 1111 961 963 1112 957 258 245 958 1107 956 1113 962 1112 1107 1108 957 1114 273 964 258 1111 960 1114 1115 1116 1117 965 1118 261 962 263 962 961 1112 1114 964 1113 965 648 274 271 964 273 965 273 1118 819 648 965 820 824 825 642 641 966 1119 1120 1121 825 967 826 641 1122 967 1123 1124 1125 1122 637 968 635 831 969 636 968 637 1126 624 970 636 635 969 974 624 1127 969 831 970 618 974 976 831 1126 970 619 975 1128 1126 1127 624 606 1128 979 976 974 1127 979 836 604 975 618 976 1129 1130 1131 619 618 975 983 598 981 619 1128 606 839 598 982 606 979 604 1132 1133 1134 836 835 604 651 838 985 837 981 835 988 651 987 983 981 837 1135 842 987 598 983 982 844 843 989 839 982 840 989 992 845 838 840 985 1136 1137 562 985 987 651 10 657 1138 842 988 987 993 1138 1139 841 988 842 1139 1140 994 841 843 844 1141 1142 996 989 845 844 1143 849 995 992 531 845 850 998 1143 538 532 531 851 997 1144 9 11 532 999 1144 1145 10 846 11 1000 1145 1146 847 846 993 1001 1146 1147 848 847 994 1147 1148 1002 849 848 995 1148 1149 1003 998 849 1143 1149 1150 1004 771 998 850 1151 1152 1006 772 771 851 1153 859 1005 853 772 999 860 1008 1153 1000 854 853 861 1007 1154 855 854 1001 1009 1154 1155 856 855 1002 1010 1155 1156 857 856 1003 1156 1157 1011 858 857 1004 1158 865 1011 859 858 1005 1014 789 1158 1153 1008 859 1015 1013 1159 860 782 1008 1159 1160 1016 861 783 782 869 1017 1016 783 1009 863 870 1161 1162 1010 864 863 1162 1163 1018 1011 865 864 1019 459 1018 865 1158 789 1020 1164 1165 789 1014 788 1021 802 1020 788 1015 867 1022 1166 1167 867 1016 1017 1023 874 1022 868 1017 869 1024 1168 1169 868 870 871 1170 1025 1024 459 871 1018 877 1026 1170 1019 460 459 878 1171 1172 802 460 1020 1173 1027 878 1021 803 802 1174 881 1173 1022 874 803 1174 1175 882 1023 875 874 1028 1031 1175 1024 1025 875 1176 1032 1028 1170 1026 1025 1177 1033 1176 1026 877 876 1178 1034 1177 876 878 1027 1179 1035 1178 1027 1173 881 1180 1036 1179 882 881 1174 1181 1037 1180 1031 882 1175 1182 1038 1181 1032 1031 1028 1183 1039 1182 1033 1032 1176 1184 1040 1183 1034 1033 1177 1185 1041 1184 1035 1034 1178 1186 1042 1185 1036 1035 1179 1187 1043 1186 1037 1036 1180 1187 1188 412 1181 1038 1037 1188 1189 413 1038 1182 1039 1044 1047 1189 1039 1183 1040 1190 1048 1044 1040 1184 1041 1191 1049 1190 1041 1185 1042 1192 900 1191 1042 1186 1043 1192 1193 901 1043 1187 412 1050 1053 1193 412 1188 413 1194 903 1050 413 1189 1047 1195 904 1194 1044 1048 1047 1056 1057 1195 1190 1049 1048 1058 381 1056 1191 900 1049 1059 1196 1197 1192 901 900 1060 373 1059 1193 1053 901 1061 1198 1199 903 1053 1050 909 1062 1061 904 903 1194 910 1200 1201 1057 904 1195 1201 1202 1063 1057 1056 381 1064 355 1063 382 381 1058 1065 1203 1204 382 1059 373 1204 1205 1066 373 1060 374 1206 914 1066 1061 1062 374 1069 343 1206 1062 909 908 1070 1068 1207 910 911 908 1207 1208 1071 1063 355 911 1208 1209 1072 1064 354 355 1210 1211 1212 913 354 1065 919 1074 1073 1066 914 913 920 1212 1213 1206 343 914 1075 1213 1214 1069 344 343 1076 1214 1215 916 344 1070 1077 1215 1216 917 916 1071 1216 1217 1078 918 917 1072 1217 1218 1079 1074 918 1073 1218 1219 1080 316 1074 919 1219 1220 1081 317 316 920 1221 1222 1083 922 317 1075 1223 929 1082 923 922 1076 930 1085 1223 1077 924 923 931 1084 1224 925 924 1078 1086 1224 1225 926 925 1079 1225 1226 1087 927 926 1080 1227 66 71 927 1081 928 1088 86 70 929 928 1082 1228 1089 70 1223 1085 929 1229 1090 1228 930 932 1085 1091 1229 1230 931 933 932 1231 1092 1230 1086 57 933 86 85 1232 1087 58 57 945 1100 946 21 1096 946 939 938 1092 1088 62 86 1233 1097 1096 70 1089 1088 1097 1234 1098 1228 1090 1089 1098 1235 1099 1229 1091 1090 1099 1236 1101 1230 1092 1091 1237 1238 1239 1231 1100 945 1106 953 1240 1102 1106 1241 1101 948 1099 1096 21 1233 1103 1241 1238 1234 1097 1233 1104 1238 1242 1235 1098 1234 1243 1105 1242 1236 1099 1235 1244 1241 1106 1101 1240 953 959 1110 958 1109 1107 958 1105 954 952 1102 1241 1103 1245 1108 1107 1103 1238 1104 1108 1246 1111 1105 1104 1242 963 1247 1248 1110 959 1243 1112 1248 1249 1249 1115 1113 1108 1111 258 1245 1107 1109 1248 1250 1249 1245 1246 1108 1116 1118 1114 1111 1247 963 963 1248 1112 1116 1251 1252 962 1113 964 1113 1112 1249 966 1117 1253 1117 819 965 273 1114 1118 1117 1118 1254 966 819 1117 824 641 967 1255 643 642 822 643 1255 967 1122 968 643 1256 1122 1257 829 635 1256 1257 637 1258 1259 1260 635 637 1257 971 1127 1126 635 829 831 976 1127 973 1126 831 830 1261 1262 1263 830 971 1126 1128 1264 980 971 973 1127 1265 1266 1267 977 976 973 978 1129 836 1264 975 977 1129 1268 837 1128 975 1264 1269 1270 1271 1128 980 979 1133 840 982 978 836 979 985 840 1132 836 1129 837 1272 986 1132 1268 983 837 1273 1274 1275 983 1268 984 843 1276 990 1133 982 984 1277 1278 990 840 1133 1132 992 991 1136 985 1132 986 564 538 1136 1135 987 986 1138 658 1279 1276 842 1135 1139 1279 1280 842 1276 843 1280 1281 1140 990 989 843 1282 995 1140 991 992 989 996 1143 1282 1136 538 992 997 1142 1283 564 9 538 1144 1283 1284 657 10 9 1145 1284 1285 1138 993 10 1146 1285 1286 994 993 1139 1147 1286 1287 995 994 1140 1287 1288 1148 1143 995 1282 1288 1289 1149 850 1143 996 1290 1291 1151 851 850 997 1292 1005 1150 999 851 1144 1006 1153 1292 1145 1000 999 1007 1152 1293 1146 1001 1000 1154 1293 1294 1002 1001 1147 1155 1294 1295 1003 1002 1148 1156 1295 1296 1004 1003 1149 1297 1298 1299 1005 1004 1150 1012 1158 1157 1292 1153 1005 1013 1299 1300 1006 860 1153 1159 1300 1301 1007 861 860 1302 1303 1304 1154 1009 861 1161 869 1160 1009 1155 1010 1162 1304 1305 1156 1011 1010 1306 1307 1308 1157 1158 1011 1164 1019 1163 1158 1012 1014 1165 1308 1309 1014 1013 1015 1166 1021 1165 1015 1159 1016 1167 1310 1311 1016 1160 869 1168 1023 1167 870 869 1161 1312 1313 1314 870 1162 1018 1315 1170 1169 1019 1018 1163 1171 877 1315 1164 1020 1019 1172 1316 1317 1021 1020 1165 1318 1173 1172 1166 1022 1021 1319 1174 1318 1167 1023 1022 1319 1029 1175 1023 1168 1024 1030 1320 1321 1169 1170 1024 1322 1176 1030 1315 877 1170 1323 1177 1322 877 1171 878 1324 1178 1323 878 1172 1173 1325 1179 1324 1173 1318 1174 1326 1180 1325 1175 1174 1319 1327 1181 1326 1028 1175 1029 1327 1328 1182 1176 1028 1030 1329 1183 1328 1177 1176 1322 1330 1184 1329 1178 1177 1323 1331 1185 1330 1179 1178 1324 1332 1186 1331 1180 1179 1325 1333 1187 1332 1326 1181 1180 1333 1334 1188 1327 1182 1181 1334 1045 1189 1183 1182 1328 1335 1336 1337 1183 1329 1184 1338 1190 1046 1184 1330 1185 1339 1191 1338 1185 1331 1186 1340 1192 1339 1186 1332 1187 1340 1051 1193 1188 1187 1333 1052 1341 1342 1188 1334 1189 1343 1194 1052 1189 1045 1044 1054 1195 1343 1044 1046 1190 1055 1344 1345 1338 1191 1190 1196 1058 1055 1339 1192 1191 1197 1346 1347 1340 1193 1192 1198 1060 1197 1051 1050 1193 1199 1348 1349 1194 1050 1052 1200 909 1199 1343 1195 1194 1201 1350 1351 1056 1195 1054 1352 1353 1354 1056 1055 1058 1203 1064 1202 1059 1058 1196 1204 1354 1355 1059 1197 1060 1356 1357 1358 1060 1198 1061 1067 1206 1205 1061 1199 909 1068 1358 1359 909 1200 910 1207 1359 1360 1201 1063 910 1360 1361 1208 1202 1064 1063 1362 1363 1210 1203 1065 1064 1364 1073 1209 1066 1065 1204 1212 919 1364 1205 1206 1066 1213 1211 1365 1067 1069 1206 1214 1365 1366 1068 1070 1069 1215 1366 1367 1207 1071 1070 1216 1367 1368 1072 1071 1208 1217 1368 1369 1073 1072 1209 1369 1370 1218 919 1073 1364 1371 1372 1373 920 919 1212 1372 1374 1221 1075 920 1213 1375 1082 1220 1076 1075 1214 1083 1223 1375 1215 1077 1076 1084 1222 1376 1216 1078 1077 1224 1376 1377 1079 1078 1217 1225 1377 1378 1080 1079 1218 1378 1379 1226 1081 1080 1219 1232 85 1226 1082 1081 1220 71 86 1232 1082 1375 1223 1228 65 256 930 1223 1083 1380 1229 256 1084 931 930 1381 1230 1380 931 1224 1086 1382 1231 1381 1086 1225 1087 1232 1227 71 1087 1226 85 1100 22 21 20 1233 21 945 1092 1231 71 70 86 1233 1383 1234 1228 70 65 1384 1235 1234 256 1229 1228 1235 1385 1236 1380 1230 1229 1236 1386 1240 1381 1231 1230 1387 20 1388 1100 1382 22 1244 1106 1389 1239 1241 1244 1240 1101 1236 1233 20 1383 1237 1390 1242 1234 1383 1384 1390 1391 1243 1385 1235 1384 1244 1095 1239 1386 1236 1385 1392 1109 1110 1389 1106 1240 1393 1245 1109 1246 1245 1394 1243 959 1105 1241 1239 1238 1247 1246 1395 1238 1237 1242 1393 1396 1397 1242 1390 1243 1248 1398 1250 1392 1110 1391 1393 1109 1392 1399 1249 1250 1246 1247 1111 1393 1394 1245 1251 1115 1399 1394 1395 1246 1400 1399 1250 1248 1247 1398 1116 1252 1254 1252 1401 1402 1113 1115 1114 1115 1249 1399 642 1253 1403 1117 1254 1253 1118 1116 1254 1253 1254 1404 966 1253 642 641 643 1122 823 822 1255 821 1405 822 1122 1256 637 822 1406 1256 1407 1408 829 1407 1257 1406 1408 1409 830 829 1257 1407 1410 1411 1412 830 829 1408 977 973 1413 830 1409 971 1264 977 1414 1409 972 971 980 1415 1266 1413 973 972 1266 1130 978 1413 1414 977 1416 1417 1418 1415 1264 1414 1131 1269 1268 1264 1415 980 1419 1133 984 980 1266 978 1420 1134 1419 978 1130 1129 1421 1422 1423 1131 1268 1129 1135 986 1273 984 1268 1269 1276 1135 1275 1419 984 1269 1424 1425 1426 1133 1419 1134 991 1278 1137 1272 1132 1134 1427 1428 536 986 1272 1273 537 765 766 1273 1275 1135 1279 767 1429 1277 1276 1275 1280 1429 1430 1277 990 1276 1431 1432 1433 1278 991 990 1141 1282 1281 1137 1136 991 1142 1433 1434 564 1136 562 1283 1434 1435 563 657 564 1284 1435 1436 658 1138 657 1285 1436 1437 1279 1139 1138 1286 1437 1438 1140 1139 1280 1287 1438 1439 1282 1140 1281 1440 1441 1442 996 1282 1141 1441 1443 1290 997 996 1142 1444 1150 1289 1144 997 1283 1151 1292 1444 1284 1145 1144 1152 1291 1445 1285 1146 1145 1293 1445 1446 1286 1147 1146 1294 1446 1447 1287 1148 1147 1295 1447 1448 1149 1148 1288 1296 1448 1449 1150 1149 1289 1450 1157 1296 1292 1150 1444 1299 1012 1450 1151 1006 1292 1300 1298 1451 1152 1007 1006 1301 1451 1452 1293 1154 1007 1453 1160 1301 1294 1155 1154 1304 1161 1453 1155 1295 1156 1305 1303 1454 1296 1157 1156 1455 1163 1305 1450 1012 1157 1308 1164 1455 1012 1299 1013 1456 1457 1458 1013 1300 1159 1310 1166 1309 1159 1301 1160 1311 1456 1459 1160 1453 1161 1460 1168 1311 1162 1161 1304 1460 1461 1169 1163 1162 1305 1312 1315 1461 1164 1163 1455 1316 1171 1312 1308 1165 1164 1462 1463 1464 1166 1165 1309 1465 1318 1317 1310 1167 1166 1466 1319 1465 1311 1168 1167 1466 1320 1029 1168 1460 1169 1467 1468 1469 1461 1315 1169 1470 1322 1321 1312 1171 1315 1471 1323 1470 1171 1316 1172 1472 1324 1471 1172 1317 1318 1473 1325 1472 1318 1465 1319 1474 1326 1473 1029 1319 1466 1474 1475 1327 1030 1029 1320 1475 1476 1328 1322 1030 1321 1477 1329 1476 1323 1322 1470 1478 1330 1477 1324 1323 1471 1479 1331 1478 1325 1324 1472 1480 1332 1479 1326 1325 1473 1481 1333 1480 1474 1327 1326 1481 1482 1334 1475 1328 1327 1482 1483 1045 1476 1329 1328 1483 1484 1046 1329 1477 1330 1335 1338 1484 1330 1478 1331 1485 1339 1335 1331 1479 1332 1486 1340 1485 1333 1332 1480 1486 1341 1051 1334 1333 1481 1342 1487 1488 1334 1482 1045 1489 1343 1342 1045 1483 1046 1489 1344 1054 1046 1484 1338 1345 1490 1491 1335 1339 1338 1346 1196 1345 1485 1340 1339 1347 1492 1493 1486 1051 1340 1348 1198 1347 1341 1052 1051 1349 1494 1495 1343 1052 1342 1350 1200 1349 1489 1054 1343 1351 1496 1497 1055 1054 1344 1498 1202 1351 1055 1345 1196 1354 1203 1498 1197 1196 1346 1355 1353 1499 1197 1347 1198 1500 1205 1355 1198 1348 1199 1358 1067 1500 1199 1349 1200 1359 1357 1501 1200 1350 1201 1360 1501 1502 1351 1202 1201 1362 1503 1504 1498 1203 1202 1505 1209 1361 1354 1204 1203 1210 1364 1505 1355 1205 1204 1211 1363 1506 1500 1067 1205 1365 1506 1507 1358 1068 1067 1366 1507 1508 1359 1207 1068 1367 1508 1509 1360 1208 1207 1368 1509 1510 1209 1208 1361 1369 1510 1511 1364 1209 1505 1512 1513 1371 1212 1364 1210 1514 1219 1370 1213 1212 1211 1373 1220 1514 1214 1213 1365 1221 1375 1373 1366 1215 1214 1222 1374 1515 1367 1216 1215 1376 1515 1516 1368 1217 1216 1377 1516 1517 1218 1217 1369 1378 1517 1518 1219 1218 1370 1519 1520 1521 1220 1219 1514 1227 1232 1379 1373 1375 1220 66 1519 1522 1221 1083 1375 78 64 1522 1083 1222 1084 1380 77 1523 1224 1084 1376 1524 1381 1523 1377 1225 1224 1525 1382 1524 1225 1378 1226 1227 1519 66 1226 1379 1232 22 1388 20 1387 1383 20 1100 1231 1382 65 71 66 1526 1384 1383 64 256 65 1384 1527 1385 77 1380 256 1385 1528 1386 1523 1381 1380 1386 1529 1389 1524 1382 1381 1387 1530 1531 1525 1388 22 1095 1244 1532 1239 1095 1533 1389 1240 1386 1383 1387 1526 1534 1237 1533 1527 1384 1526 1535 1390 1534 1528 1385 1527 1536 1391 1535 1528 1529 1386 1094 1533 1095 1389 1532 1244 1392 1396 1393 1393 1397 1394 1391 1110 1243 1237 1239 1533 1394 1537 1395 1390 1237 1534 1395 1538 1398 1391 1390 1535 1539 1397 1540 1396 1392 1536 1400 1250 1541 1542 1399 1400 1395 1398 1247 1397 1537 1394 1401 1251 1542 1537 1538 1395 1542 1400 1543 1398 1541 1250 1402 1544 1545 1546 1547 1403 1115 1251 1116 1251 1399 1542 1255 1403 1547 1253 1404 1403 1254 1252 1404 1404 1546 1403 642 1403 1255 643 822 1256 1548 1405 821 1548 1123 1405 1256 1406 1257 1405 1549 1406 1408 1550 1258 1550 1407 1549 1258 1551 1409 1408 1407 1550 1413 972 1552 1409 1408 1258 1263 1414 1413 1409 1551 972 1415 1414 1262 1551 1552 972 1553 1554 1555 1552 1263 1413 1130 1265 1417 1262 1414 1263 1417 1270 1131 1267 1415 1262 1270 1416 1556 1415 1267 1266 1557 1558 1559 1266 1265 1130 1422 1272 1134 1417 1131 1130 1273 1272 1421 1270 1269 1131 1560 1561 1562 1271 1419 1269 1277 1275 1424 1419 1271 1420 1278 1426 1563 1422 1134 1420 1137 1563 1427 1272 1422 1421 1427 535 562 1273 1421 1274 767 765 1564 1424 1275 1274 1429 1564 1565 1277 1424 1426 1431 1566 1567 1277 1426 1278 1568 1281 1430 1563 1137 1278 1433 1141 1568 1427 562 1137 1434 1432 1569 535 563 562 1435 1569 1570 766 658 563 1436 1570 1571 767 1279 658 1437 1571 1572 1429 1280 1279 1438 1572 1573 1281 1280 1430 1574 1440 1575 1141 1281 1568 1439 1576 1288 1142 1141 1433 1442 1289 1576 1283 1142 1434 1290 1444 1442 1435 1284 1283 1291 1443 1577 1436 1285 1284 1445 1577 1578 1437 1286 1285 1446 1578 1579 1438 1287 1286 1447 1579 1580 1439 1288 1287 1448 1580 1581 1289 1288 1576 1582 1583 1584 1444 1289 1442 1297 1450 1449 1290 1151 1444 1298 1582 1585 1291 1152 1151 1451 1585 1586 1445 1293 1152 1452 1586 1587 1446 1294 1293 1302 1453 1452 1294 1447 1295 1303 1588 1589 1295 1448 1296 1454 1589 1590 1449 1450 1296 1454 1306 1455 1450 1297 1299 1307 1591 1592 1299 1298 1300 1307 1593 1309 1300 1451 1301 1456 1310 1593 1453 1301 1452 1594 1595 1596 1453 1302 1304 1597 1460 1459 1305 1304 1303 1597 1313 1461 1454 1455 1305 1314 1598 1599 1308 1455 1306 1600 1316 1314 1307 1309 1308 1600 1601 1317 1310 1309 1593 1462 1465 1601 1456 1311 1310 1602 1466 1462 1459 1460 1311 1602 1603 1320 1460 1597 1461 1603 1604 1321 1313 1312 1461 1467 1470 1604 1314 1316 1312 1605 1471 1467 1316 1600 1317 1606 1472 1605 1317 1601 1465 1607 1473 1606 1465 1462 1466 1608 1474 1607 1320 1466 1602 1608 1609 1475 1321 1320 1603 1609 1610 1476 1470 1321 1604 1610 1611 1477 1471 1470 1467 1612 1478 1611 1472 1471 1605 1613 1479 1612 1473 1472 1606 1614 1480 1613 1474 1473 1607 1614 1615 1481 1608 1475 1474 1615 1616 1482 1609 1476 1475 1616 1617 1483 1610 1477 1476 1617 1336 1484 1478 1477 1611 1618 1619 1620 1478 1612 1479 1621 1485 1337 1479 1613 1480 1622 1486 1621 1481 1480 1614 1622 1487 1341 1482 1481 1615 1623 1624 1625 1482 1616 1483 1626 1489 1488 1483 1617 1484 1626 1490 1344 1484 1336 1335 1491 1627 1628 1337 1485 1335 1492 1346 1491 1621 1486 1485 1629 1630 1631 1622 1341 1486 1494 1348 1493 1487 1342 1341 1632 1633 1634 1489 1342 1488 1496 1350 1495 1626 1344 1489 1497 1632 1635 1345 1344 1490 1352 1498 1497 1346 1345 1491 1353 1636 1637 1347 1346 1492 1499 1637 1638 1347 1493 1348 1356 1500 1499 1349 1348 1494 1357 1639 1640 1349 1495 1350 1501 1640 1641 1350 1496 1351 1502 1641 1642 1497 1498 1351 1502 1643 1361 1352 1354 1498 1362 1505 1643 1354 1353 1355 1363 1504 1644 1499 1500 1355 1506 1644 1645 1356 1358 1500 1507 1645 1646 1357 1359 1358 1508 1646 1647 1501 1360 1359 1509 1647 1648 1502 1361 1360 1510 1648 1649 1505 1361 1643 1512 1650 1651 1210 1505 1362 1652 1370 1511 1211 1210 1363 1371 1514 1652 1506 1365 1211 1372 1513 1653 1507 1366 1365 1374 1653 1654 1508 1367 1366 1515 1654 1655 1509 1368 1367 1516 1655 1656 1510 1369 1368 1517 1656 1657 1370 1369 1511 1518 1657 1658 1514 1370 1652 1518 1659 1379 1373 1514 1371 1519 1227 1659 1372 1221 1373 1522 1521 1660 1374 1222 1221 78 1660 83 1515 1376 1222 72 1523 79 1377 1376 1516 1524 72 1661 1517 1378 1377 1662 1525 1661 1518 1379 1378 1519 1521 1522 1659 1227 1379 1388 1530 1387 1531 1526 1387 22 1382 1525 64 66 1522 1526 1663 1527 78 77 64 1664 1528 1527 79 1523 77 1528 254 1529 72 1524 1523 1529 253 1532 1524 1661 1525 1665 1531 1666 1662 1530 1388 1667 1668 1669 1533 1094 1670 1532 1389 1529 1526 1531 1663 1534 1670 1671 1527 1663 1664 1672 1535 1671 254 1528 1664 1673 1536 1672 253 1529 254 1674 1670 1094 1532 1093 1095 1396 1540 1397 1539 1537 1397 1536 1392 1391 1533 1670 1534 1537 1675 1538 1535 1534 1671 1538 1676 1541 1536 1535 1672 1677 1539 1678 1540 1396 1673 1543 1400 1679 1542 1543 1680 1538 1541 1398 1539 1675 1537 1544 1401 1680 1675 1676 1538 1545 1546 1402 1541 1679 1400 1545 1681 1682 1252 1402 1404 1251 1401 1252 1680 1401 1542 1547 1683 1684 821 823 1547 1404 1402 1546 1546 1683 1547 1255 1547 823 822 1405 1406 1124 1123 1548 1685 1686 1687 1406 1549 1407 1123 1688 1549 1689 1690 1691 1688 1259 1550 1260 1412 1551 1258 1550 1259 1692 1263 1552 1551 1258 1260 1693 1694 1695 1551 1412 1552 1267 1262 1554 1412 1692 1552 1265 1553 1418 1692 1261 1263 1696 1697 1698 1554 1262 1261 1699 1696 1700 1267 1554 1553 1556 1557 1271 1267 1553 1265 1701 1422 1420 1265 1418 1417 1702 1703 1704 1416 1270 1417 1561 1274 1421 1556 1271 1270 1424 1274 1560 1557 1420 1271 1705 1706 1707 1701 1420 1557 1563 1708 1428 1423 1422 1701 1709 1710 1428 1561 1421 1423 660 542 1711 1561 1560 1274 1564 764 1712 1424 1560 1425 1565 1712 1713 1426 1425 1708 1565 1714 1430 1708 1563 1426 1431 1568 1714 1428 1427 1563 1432 1567 1715 536 535 1427 1569 1715 1716 537 766 535 1570 1716 1717 765 767 766 1571 1717 1718 1564 1429 767 1572 1718 1719 1565 1430 1429 1720 1575 1721 1568 1430 1714 1573 1722 1439 1433 1568 1431 1722 1440 1576 1432 1434 1433 1441 1574 1723 1569 1435 1434 1443 1723 1724 1570 1436 1435 1577 1724 1725 1571 1437 1436 1578 1725 1726 1572 1438 1437 1579 1726 1727 1573 1439 1438 1580 1727 1728 1722 1576 1439 1729 1583 1730 1442 1576 1440 1581 1731 1449 1290 1442 1441 1582 1297 1731 1443 1291 1290 1585 1584 1732 1577 1445 1291 1586 1732 1733 1578 1446 1445 1734 1735 1736 1579 1447 1446 1587 1588 1302 1447 1580 1448 1589 1735 1737 1448 1581 1449 1590 1737 1738 1731 1297 1449 1590 1591 1306 1297 1582 1298 1592 1739 1740 1298 1585 1451 1592 1457 1593 1452 1451 1586 1458 1741 1742 1302 1452 1587 1458 1743 1459 1302 1588 1303 1594 1597 1743 1454 1303 1589 1594 1598 1313 1590 1306 1454 1599 1744 1745 1307 1306 1591 1746 1600 1599 1592 1593 1307 1746 1463 1601 1457 1456 1593 1464 1747 1748 1458 1459 1456 1749 1602 1464 1743 1597 1459 1749 1750 1603 1597 1594 1313 1750 1468 1604 1313 1598 1314 1751 1752 1753 1599 1600 1314 1754 1605 1469 1600 1746 1601 1755 1606 1754 1601 1463 1462 1756 1607 1755 1462 1464 1602 1757 1608 1756 1603 1602 1749 1757 1758 1609 1604 1603 1750 1758 1759 1610 1467 1604 1468 1759 1760 1611 1605 1467 1469 1761 1612 1760 1606 1605 1754 1762 1613 1761 1607 1606 1755 1763 1614 1762 1608 1607 1756 1763 1764 1615 1757 1609 1608 1764 1765 1616 1758 1610 1609 1765 1766 1617 1759 1611 1610 1766 1767 1336 1612 1611 1760 1767 1768 1337 1612 1761 1613 1618 1621 1768 1613 1762 1614 1769 1622 1618 1615 1614 1763 1769 1770 1487 1616 1615 1764 1770 1771 1488 1616 1765 1617 1623 1626 1771 1617 1766 1336 1623 1627 1490 1336 1767 1337 1772 1773 1774 1768 1621 1337 1775 1492 1628 1618 1622 1621 1775 1776 1493 1769 1487 1622 1629 1494 1776 1770 1488 1487 1629 1777 1495 1626 1488 1771 1632 1496 1777 1623 1490 1626 1778 1779 1780 1491 1490 1627 1636 1352 1635 1492 1491 1628 1637 1779 1781 1493 1492 1775 1782 1783 1784 1493 1776 1494 1639 1356 1638 1495 1494 1629 1640 1783 1785 1495 1777 1496 1641 1785 1786 1496 1632 1497 1787 1788 1789 1635 1352 1497 1642 1503 1643 1352 1636 1353 1504 1788 1790 1353 1637 1499 1644 1790 1791 1499 1638 1356 1645 1791 1792 1639 1357 1356 1646 1792 1793 1640 1501 1357 1647 1793 1794 1641 1502 1501 1795 1796 1797 1642 1643 1502 1798 1650 1795 1362 1643 1503 1649 1799 1511 1363 1362 1504 1512 1652 1799 1644 1506 1363 1513 1651 1800 1645 1507 1506 1653 1800 1801 1646 1508 1507 1654 1801 1802 1647 1509 1508 1655 1802 1803 1648 1510 1509 1656 1803 1804 1649 1511 1510 1657 1804 1805 1652 1511 1799 1806 1807 1808 1371 1652 1512 1658 1520 1659 1513 1372 1371 1521 1807 1809 1653 1374 1372 1660 1809 1810 1654 1515 1374 83 1810 1811 1655 1516 1515 91 1812 1813 1656 1517 1516 1814 1661 74 1657 1518 1517 1815 1662 1814 1658 1659 1518 1809 1660 1521 1520 1519 1659 1530 1666 1531 1665 1663 1531 1388 1525 1662 78 1522 1660 1816 1664 1663 83 79 78 1664 1817 254 79 73 72 1818 1819 1820 74 1661 72 253 1821 1093 1814 1662 1661 1819 1665 1822 1530 1815 1666 1674 1094 1823 1824 1670 1674 1093 1532 253 1663 1665 1816 1825 1671 1824 1664 1816 1817 1672 1825 1826 254 1817 252 1827 1673 1826 1821 253 252 1824 1674 1667 1823 1094 1093 1540 1678 1539 1677 1675 1539 1673 1396 1536 1670 1824 1671 1828 1676 1675 1671 1825 1672 1676 1829 1679 1673 1672 1826 1830 1677 1831 1678 1540 1827 1680 1832 1833 1833 1681 1544 1676 1679 1541 1828 1675 1677 1832 1834 1833 1828 1829 1676 1682 1683 1545 1679 1835 1543 1543 1832 1680 1682 1836 1837 1401 1544 1402 1544 1680 1833 1548 1684 1838 1684 821 1547 1546 1545 1683 1684 1683 1839 1548 821 1684 1405 1123 1549 1121 1125 1124 1120 1125 1121 1549 1688 1550 1125 1840 1688 1841 1410 1260 1840 1841 1259 1842 1843 1844 1260 1259 1841 1695 1261 1692 1260 1410 1412 1554 1261 1694 1692 1412 1411 1845 1846 1847 1411 1695 1692 1418 1848 1697 1694 1261 1695 1697 1699 1416 1554 1694 1555 1699 1558 1556 1848 1553 1555 1849 1850 1851 1553 1848 1418 1704 1423 1701 1697 1416 1418 1703 1561 1423 1416 1699 1556 1852 1853 1854 1558 1557 1556 1425 1560 1705 1559 1701 1557 1708 1425 1707 1704 1701 1559 1855 1856 1857 1703 1423 1704 536 1710 713 1561 1703 1562 764 543 1858 1562 1705 1560 1712 1858 1859 1707 1425 1705 1860 1861 1862 1707 1709 1708 1713 1566 1714 1709 1428 1708 1567 1861 1863 1710 536 1428 1715 1863 1864 536 713 537 1716 1864 1865 544 765 537 1717 1865 1866 764 1564 765 1718 1866 1867 1712 1565 1564 1868 1721 1869 1713 1714 1565 1719 1870 1573 1431 1714 1566 1870 1575 1722 1567 1432 1431 1871 1574 1720 1715 1569 1432 1723 1871 1872 1716 1570 1569 1724 1872 1873 1717 1571 1570 1725 1873 1874 1718 1572 1571 1726 1874 1875 1719 1573 1572 1727 1875 1876 1870 1722 1573 1728 1876 1877 1575 1440 1722 1728 1878 1581 1441 1440 1574 1878 1583 1731 1723 1443 1441 1584 1729 1879 1724 1577 1443 1732 1879 1880 1725 1578 1577 1733 1880 1881 1726 1579 1578 1733 1882 1587 1727 1580 1579 1882 1735 1588 1580 1728 1581 1737 1734 1883 1581 1878 1731 1884 1885 1886 1583 1582 1731 1738 1739 1591 1582 1584 1585 1740 1885 1887 1585 1732 1586 1740 1741 1457 1587 1586 1733 1742 1888 1889 1588 1587 1882 1742 1595 1743 1589 1588 1735 1596 1890 1891 1590 1589 1737 1596 1744 1598 1738 1591 1590 1745 1892 1893 1592 1591 1739 1894 1746 1745 1740 1457 1592 1894 1747 1463 1741 1458 1457 1748 1895 1896 1742 1743 1458 1897 1749 1748 1595 1594 1743 1897 1898 1750 1594 1596 1598 1898 1899 1468 1598 1744 1599 1899 1900 1469 1745 1746 1599 1751 1754 1900 1746 1894 1463 1901 1755 1751 1463 1747 1464 1902 1756 1901 1464 1748 1749 1903 1757 1902 1750 1749 1897 1903 1904 1758 1468 1750 1898 1904 1905 1759 1469 1468 1899 1905 1906 1760 1754 1469 1900 1907 1761 1906 1755 1754 1751 1908 1762 1907 1756 1755 1901 1909 1763 1908 1902 1757 1756 1909 1910 1764 1903 1758 1757 1910 1911 1765 1904 1759 1758 1911 1912 1766 1905 1760 1759 1912 1913 1767 1906 1761 1760 1913 1619 1768 1762 1761 1907 1620 1914 1915 1762 1908 1763 1916 1769 1620 1764 1763 1909 1916 1917 1770 1765 1764 1910 1917 1624 1771 1766 1765 1911 1625 1918 1919 1766 1912 1767 1625 1920 1627 1767 1913 1768 1920 1921 1628 1619 1618 1768 1772 1775 1921 1620 1769 1618 1772 1630 1776 1769 1916 1770 1631 1922 1923 1917 1771 1770 1631 1633 1777 1624 1623 1771 1634 1924 1925 1625 1627 1623 1634 1926 1635 1628 1627 1920 1779 1636 1926 1775 1628 1921 1781 1778 1927 1776 1775 1772 1781 1928 1638 1776 1630 1629 1928 1783 1639 1777 1629 1631 1785 1782 1929 1777 1633 1632 1786 1929 1930 1632 1634 1635 1786 1931 1642 1635 1926 1636 1931 1788 1503 1636 1779 1637 1790 1787 1932 1637 1781 1638 1791 1932 1933 1638 1928 1639 1792 1933 1934 1783 1640 1639 1793 1934 1935 1785 1641 1640 1936 1797 1937 1786 1642 1641 1794 1938 1648 1931 1503 1642 1938 1796 1649 1504 1503 1788 1796 1650 1799 1790 1644 1504 1939 1651 1798 1791 1645 1644 1800 1939 1940 1792 1646 1645 1801 1940 1941 1793 1647 1646 1802 1941 1942 1794 1648 1647 1803 1942 1943 1938 1649 1648 1804 1943 1944 1796 1799 1649 1945 1808 1946 1650 1512 1799 1805 1947 1658 1513 1512 1651 1947 1807 1520 1800 1653 1513 1809 1806 1948 1801 1654 1653 1810 1948 1949 1802 1655 1654 1950 84 1951 1803 1656 1655 1811 75 73 1657 1656 1804 60 1814 76 1805 1658 1657 1952 1815 60 1947 1520 1658 1948 1810 1809 1807 1521 1520 1666 1822 1665 1819 1816 1665 1530 1662 1815 1660 1810 83 1953 1817 1816 73 83 1811 68 252 1817 75 74 73 252 67 1821 74 76 1814 1821 1954 1823 60 1815 1814 1955 1956 1957 1952 1822 1666 1667 1674 1958 1824 1667 1669 1823 1093 1821 1816 1819 1953 1959 1825 1669 1817 1953 68 1960 1826 1959 67 252 68 1961 1827 1960 1821 67 1954 1831 1677 1678 1958 1674 1823 1830 1828 1677 1829 1828 1962 1827 1540 1673 1824 1669 1825 1835 1829 1963 1825 1959 1826 1830 1964 1965 1826 1960 1827 1832 1966 1834 1831 1678 1961 1833 1834 1967 1835 1832 1543 1829 1835 1679 1830 1962 1828 1836 1681 1967 1962 1963 1829 1968 1967 1834 1832 1835 1966 1682 1837 1839 1837 1969 1970 1544 1681 1545 1681 1833 1967 1124 1838 1971 1684 1839 1838 1683 1682 1839 1838 1839 1972 1548 1838 1124 1125 1688 1123 1973 1120 1119 1973 1974 1120 1688 1840 1259 1120 1975 1840 1976 1977 1410 1976 1841 1975 1977 1978 1411 1410 1841 1976 1843 1979 1980 1411 1410 1977 1555 1694 1846 1411 1978 1695 1848 1555 1845 1978 1693 1695 1981 1982 1983 1846 1694 1693 1984 1985 1986 1845 1555 1846 1700 1849 1558 1848 1845 1698 1849 1987 1559 1848 1698 1697 1988 1987 1851 1697 1696 1699 1853 1562 1703 1700 1558 1699 1705 1562 1852 1558 1849 1559 1989 1990 1991 1987 1704 1559 1709 1707 1855 1702 1704 1987 1710 1857 714 1853 1703 1702 1992 661 1711 1853 1852 1562 1858 662 1993 1852 1706 1705 1859 1993 1994 1855 1707 1706 1859 1995 1713 1709 1855 1857 1995 1861 1566 1857 1710 1709 1996 1863 1860 713 1710 714 1864 1996 1997 713 542 544 1865 1997 1998 543 764 544 1866 1998 1999 1858 1712 764 2000 1869 2001 1859 1713 1712 1867 2002 1719 1995 1566 1713 2002 1721 1870 1566 1861 1567 2003 1720 1868 1863 1715 1567 2004 1871 2003 1864 1716 1715 1872 2004 2005 1865 1717 1716 1873 2005 2006 1866 1718 1717 1874 2006 2007 1867 1719 1718 1875 2007 2008 2002 1870 1719 1876 2008 2009 1721 1575 1870 2010 2011 2012 1720 1574 1575 1877 1730 1878 1871 1723 1574 2013 1729 2011 1872 1724 1723 2014 1879 2013 1873 1725 1724 1880 2014 2015 1874 1726 1725 2016 2017 2018 1875 1727 1726 1881 1736 1882 1727 1876 1728 2019 1734 2017 1728 1877 1878 1883 2019 2020 1878 1730 1583 1883 2021 1738 1583 1729 1584 2021 1885 1739 1584 1879 1732 1887 1884 2022 1732 1880 1733 1887 1888 1741 1882 1733 1881 1889 2023 2024 1735 1882 1736 1889 1890 1595 1737 1735 1734 1891 2025 2026 1738 1737 1883 1891 1892 1744 2021 1739 1738 2027 2028 2029 1740 1739 1885 2030 1894 1893 1887 1741 1740 2030 1895 1747 1888 1742 1741 2031 2032 2033 1889 1595 1742 2034 1897 1896 1890 1596 1595 2034 2035 1898 1596 1891 1744 2035 2036 1899 1744 1892 1745 2036 1752 1900 1894 1745 1893 1753 2037 2038 1894 2030 1747 2039 1901 1753 1747 1895 1748 2040 1902 2039 1748 1896 1897 2040 2041 1903 1898 1897 2034 2041 2042 1904 1899 1898 2035 2042 2043 1905 1900 1899 2036 2043 2044 1906 1751 1900 1752 2044 2045 1907 1901 1751 1753 2046 1908 2045 1902 1901 2039 2047 1909 2046 2040 1903 1902 2047 2048 1910 2041 1904 1903 2048 2049 1911 2042 1905 1904 2049 2050 1912 2043 1906 1905 2050 2051 1913 2044 1907 1906 2051 1914 1619 1908 1907 2045 2052 2053 2054 1909 1908 2046 2055 1916 1915 1910 1909 2047 2055 2056 1917 1911 1910 2048 2056 1918 1624 1912 1911 2049 1919 2057 2058 1912 2050 1913 1919 2059 1920 1913 2051 1619 2059 1773 1921 1619 1914 1620 1774 2060 2061 1915 1916 1620 1774 1922 1630 1916 2055 1917 1923 2062 2063 2056 1624 1917 1923 1924 1633 1918 1625 1624 1925 2064 2065 1919 1920 1625 1925 1780 1926 2059 1921 1920 2066 1778 2067 1772 1921 1773 1927 2066 2068 1630 1772 1774 1927 1784 1928 1631 1630 1922 2069 1782 2070 1633 1631 1923 1929 2069 2071 1633 1924 1634 2072 2073 2074 1634 1925 1926 1930 1789 1931 1779 1926 1780 2075 1787 2073 1779 1778 1781 1932 2075 2076 1781 1927 1928 1933 2076 2077 1928 1784 1783 1934 2077 2078 1782 1785 1783 2079 1937 2080 1929 1786 1785 1935 2081 1794 1930 1931 1786 2081 1797 1938 1931 1789 1788 2082 1795 1936 1787 1790 1788 2083 1798 2082 1932 1791 1790 2084 1939 2083 1933 1792 1791 1940 2084 2085 1934 1793 1792 1941 2085 2086 1935 1794 1793 1942 2086 2087 2081 1938 1794 1943 2087 2088 1797 1796 1938 2089 1946 2090 1795 1650 1796 1944 2091 1805 1798 1651 1650 2091 1808 1947 1939 1800 1651 2092 1806 1945 1940 1801 1800 1948 2092 2093 1941 1802 1801 1949 2093 2094 1942 1803 1802 1949 2095 1811 1943 1804 1803 2095 84 75 1804 1944 1805 61 1950 87 2091 1947 1805 2096 1952 59 1947 1808 1807 1948 2093 1949 1806 1809 1807 1822 1820 1819 1818 1953 1819 1666 1815 1952 1810 1949 1811 1953 2097 68 1811 2095 75 2098 82 81 75 84 76 2099 1954 67 61 60 76 1954 2100 1958 60 59 1952 2101 1818 2102 1822 2096 1820 1668 1667 2103 2104 1669 1668 1958 1823 1954 1953 1818 2097 1959 2104 2105 68 2097 69 2106 1960 2105 67 69 2099 2107 1961 2106 2100 1954 2099 2104 1668 2108 2103 1667 1958 1831 1964 1830 1830 1965 1962 1961 1678 1827 1669 2104 1959 1962 2109 1963 1960 1959 2105 1963 2110 1966 1961 1960 2106 1957 1965 1955 1964 1831 2107 1968 1834 2111 2112 1967 1968 1963 1966 1835 1965 2109 1962 1969 1836 2112 2109 2110 1963 2112 1968 2113 1966 2111 1834 1970 2114 2115 2116 1971 2117 1681 1836 1682 1836 1967 2112 1121 1971 2116 1838 1972 1971 1839 1837 1972 1972 2117 1971 1124 1971 1121 1125 1120 1840 2118 1974 1973 2118 1689 1974 1840 1975 1841 1974 2119 1975 1977 2120 2121 2120 1976 2119 2121 2122 1978 1977 1976 2120 1846 1693 2123 1978 1977 2121 2124 2125 2126 1978 2122 1693 1698 1845 1982 2123 1693 2122 1696 1981 1985 1847 1846 2123 1985 1850 1700 1982 1845 1847 2127 2128 2129 1698 1982 1981 2130 2127 2131 1698 1981 1696 2132 1853 1702 1696 1985 1700 2133 1854 2132 1700 1850 1849 1990 1706 1852 1851 1987 1849 1855 1706 1989 1987 1988 1702 1856 1989 2134 2132 1702 1988 714 2135 1711 2132 1854 1853 2136 662 659 1854 1990 1852 1993 2136 2137 1989 1706 1990 2138 2139 2140 1855 1989 1856 1994 1862 1995 2135 1857 1856 2141 1860 2139 1857 2135 714 2142 1996 2141 714 1711 542 1997 2142 2143 542 660 543 1998 2143 2144 662 1858 543 2145 2001 2146 1993 1859 1858 1999 2147 1867 1994 1995 1859 2147 1869 2002 1995 1862 1861 2148 1868 2000 1861 1860 1863 2149 2003 2148 1996 1864 1863 2150 2004 2149 1997 1865 1864 2151 2005 2150 1998 1866 1865 2006 2151 2152 1999 1867 1866 2007 2152 2153 2147 2002 1867 2008 2153 2154 1869 1721 2002 2155 2012 2156 1868 1720 1721 2009 2157 1877 2003 1871 1720 2157 2011 1730 1871 2004 1872 2158 2013 2010 2005 1873 1872 2159 2014 2158 2006 1874 1873 2015 2159 2160 2007 1875 1874 2015 2161 1881 2008 1876 1875 2161 2017 1736 1876 2009 1877 2162 2019 2016 1877 2157 1730 2020 2162 2163 1730 2011 1729 2020 1886 2021 1879 1729 2013 2164 1884 2165 1879 2014 1880 2166 2167 2168 1880 2015 1881 2022 2023 1888 1736 1881 2161 2024 2167 2169 1734 1736 2017 2024 2025 1890 1883 1734 2019 2026 2170 2171 2021 1883 2020 2026 2172 1892 1886 1885 2021 2172 2173 1893 1887 1885 1884 2173 2028 2030 2022 1888 1887 2028 2174 1895 2023 1889 1888 2174 2175 1896 2024 1890 1889 2031 2034 2175 2025 1891 1890 2031 2176 2035 1891 2026 1892 2176 2177 2036 1892 2172 1893 2177 2037 1752 2030 1893 2173 2178 2179 2180 2030 2028 1895 2181 2039 2038 1895 2174 1896 2182 2040 2181 1896 2175 2034 2182 2183 2041 2035 2034 2031 2183 2184 2042 2036 2035 2176 2184 2185 2043 1752 2036 2177 2185 2186 2044 1753 1752 2037 2186 2187 2045 2039 1753 2038 2188 2046 2187 2040 2039 2181 2188 2189 2047 2182 2041 2040 2189 2190 2048 2183 2042 2041 2190 2191 2049 2184 2043 2042 2191 2192 2050 2185 2044 2043 2192 2193 2051 2186 2045 2044 2193 2194 1914 2187 2046 2045 2194 2195 1915 2047 2046 2188 2052 2055 2195 2048 2047 2189 2052 2196 2056 2049 2048 2190 2196 2057 1918 2050 2049 2191 2197 2198 2199 2050 2192 2051 2058 2200 2059 2051 2193 1914 2200 2060 1773 1914 2194 1915 2061 2201 2202 2195 2055 1915 2061 2062 1922 2055 2052 2056 2063 2203 2204 2196 1918 2056 2063 2064 1924 2057 1919 1918 2065 2205 2206 2058 2059 1919 2065 2067 1780 2200 1773 2059 2207 2066 2208 1774 1773 2060 2209 2210 2211 1922 1774 2061 2068 2070 1784 1923 1922 2062 2212 2069 2210 1924 1923 2063 2071 2212 2213 1924 2064 1925 2071 2214 1930 1925 2065 1780 2214 2073 1789 1778 1780 2067 2215 2075 2072 1778 2066 1927 2076 2215 2216 1927 2068 1784 2077 2216 2217 1784 2070 1782 2218 2080 2219 2069 1929 1782 2078 2220 1935 2071 1930 1929 2220 1937 2081 1930 2214 1789 2221 1936 2079 1789 2073 1787 2222 2082 2221 2075 1932 1787 2223 2083 2222 2076 1933 1932 2224 2084 2223 2077 1934 1933 2085 2224 2225 2078 1935 1934 2086 2225 2226 2220 2081 1935 2087 2226 2227 1937 1797 2081 2228 2090 2229 1936 1795 1797 2088 2230 1944 2082 1798 1795 2230 1946 2091 1798 2083 1939 2231 1945 2089 2084 1940 1939 2232 2092 2231 2085 1941 1940 2093 2232 2233 2086 1942 1941 2094 2233 2234 2087 1943 1942 2094 1951 2095 1943 2088 1944 2235 1950 2236 1944 2230 2091 87 2235 2237 1946 1808 2091 89 2096 88 1808 1945 1806 2093 2233 2094 2092 1948 1806 1820 2102 1818 2101 2097 1818 1822 1952 2096 2095 1949 2094 2238 69 2097 2095 1951 84 69 2239 2099 84 1950 61 2099 2240 2100 61 87 59 2100 2241 2103 88 2096 59 2242 2101 2243 1820 89 2102 2108 1668 2244 2104 2108 2245 2103 1958 2100 2097 2101 2238 2246 2105 2245 2239 69 2238 2247 2106 2246 2099 2239 2240 2248 2107 2247 2100 2240 2241 2245 2108 2249 2244 1668 2103 1964 1955 1965 1957 2109 1965 2107 1831 1961 2104 2245 2105 2109 2250 2110 2105 2246 2106 2110 2251 2111 2107 2106 2247 2252 1957 1956 1955 1964 2248 2113 1968 2253 2112 2113 2254 2110 2111 1966 1957 2250 2109 2114 1969 2254 2250 2251 2110 2115 2117 1970 2111 2253 1968 2115 2255 2256 1837 1970 1972 1836 1969 1837 2254 1969 2112 2116 2257 2258 1119 1121 2116 1972 1970 2117 2116 2117 2257 1973 1119 2116 1120 1974 1975 1690 1689 2118 2259 2260 2261 1975 2119 1976 1689 2262 2119 2121 2263 1844 2262 2263 2120 1844 1980 2122 2121 2120 2263 2126 1847 2123 2121 1844 2122 1982 1847 2125 2122 1980 2123 2264 2265 2266 1980 2126 2123 2267 2264 2268 2125 1847 2126 1850 1984 2128 1982 2125 1983 2128 2130 1851 1981 1983 1986 2130 2269 1988 1981 1986 1985 2270 2271 2272 1985 1984 1850 2273 1990 1854 1850 2128 1851 2274 1991 2273 1851 2130 1988 2275 2276 2277 2269 2132 1988 2135 1856 2278 2133 2132 2269 2279 1992 2278 1854 2133 2273 2280 2136 708 1991 1990 2273 2137 2280 2281 1989 1991 2134 2137 2282 1994 1856 2134 2278 2282 2139 1862 2135 2278 1992 2283 2141 2138 2135 1992 1711 2284 2142 2283 1711 661 660 2143 2284 2285 660 659 662 2286 2146 2287 2136 1993 662 2144 2288 1999 2137 1994 1993 2288 2001 2147 1994 2282 1862 2289 2000 2145 1862 2139 1860 2290 2148 2289 1860 2141 1996 2291 2149 2290 2142 1997 1996 2292 2150 2291 2143 1998 1997 2293 2151 2292 2144 1999 1998 2152 2293 2294 2288 2147 1999 2153 2294 2295 2001 1869 2147 2296 2156 2297 2000 1868 1869 2154 2298 2009 2148 2003 1868 2298 2012 2157 2003 2149 2004 2299 2010 2155 2004 2150 2005 2300 2158 2299 2151 2006 2005 2301 2159 2300 2152 2007 2006 2160 2301 2302 2153 2008 2007 2160 2018 2161 2008 2154 2009 2303 2016 2304 2009 2298 2157 2305 2162 2303 2157 2012 2011 2306 2307 2308 2011 2010 2013 2163 2165 1886 2014 2013 2158 2309 2164 2307 2014 2159 2015 2164 2310 2022 2015 2160 2161 2310 2167 2023 2017 2161 2018 2311 2312 2313 2019 2017 2016 2169 2170 2025 2020 2019 2162 2314 2315 2316 1886 2020 2163 2171 2317 2172 2165 1884 1886 2317 2029 2173 2164 2022 1884 2318 2027 2319 2310 2023 2022 2027 2320 2174 2167 2024 2023 2320 2032 2175 2024 2169 2025 2033 2321 2322 2170 2026 2025 2033 2323 2176 2026 2171 2172 2323 2324 2177 2172 2317 2173 2324 2325 2037 2028 2173 2029 2325 2326 2038 2028 2027 2174 2327 2181 2326 2174 2320 2175 2328 2182 2327 2175 2032 2031 2328 2329 2183 2176 2031 2033 2329 2330 2184 2177 2176 2323 2330 2331 2185 2037 2177 2324 2331 2332 2186 2038 2037 2325 2332 2333 2187 2181 2038 2326 2333 2334 2188 2182 2181 2327 2334 2335 2189 2328 2183 2182 2335 2336 2190 2329 2184 2183 2336 2337 2191 2330 2185 2184 2337 2338 2192 2331 2186 2185 2338 2339 2193 2332 2187 2186 2339 2340 2194 2333 2188 2187 2340 2053 2195 2334 2189 2188 2054 2341 2342 2190 2189 2335 2054 2343 2196 2191 2190 2336 2343 2344 2057 2192 2191 2337 2344 2345 2058 2192 2338 2193 2345 2198 2200 2193 2339 2194 2198 2201 2060 2194 2340 2195 2202 2346 2347 2053 2052 2195 2202 2203 2062 2052 2054 2196 2348 2349 2350 2343 2057 2196 2204 2205 2064 2344 2058 2057 2206 2349 2351 2345 2200 2058 2206 2208 2067 2198 2060 2200 2352 2207 2353 2061 2060 2201 2207 2354 2068 2062 2061 2202 2354 2210 2070 2063 2062 2203 2355 2212 2209 2064 2063 2204 2356 2357 2358 2064 2205 2065 2213 2074 2214 2067 2065 2206 2359 2072 2357 2066 2067 2208 2360 2215 2359 2066 2207 2068 2216 2360 2361 2068 2354 2070 2362 2219 2363 2070 2210 2069 2217 2364 2078 2212 2071 2069 2364 2080 2220 2071 2213 2214 2365 2079 2218 2214 2074 2073 2366 2221 2365 2073 2072 2075 2367 2222 2366 2215 2076 2075 2368 2223 2367 2216 2077 2076 2369 2224 2368 2217 2078 2077 2225 2369 2370 2364 2220 2078 2226 2370 2371 2080 1937 2220 2372 2229 2373 2079 1936 1937 2227 2374 2088 2221 2082 1936 2374 2090 2230 2082 2222 2083 2375 2089 2228 2083 2223 2084 2376 2231 2375 2224 2085 2084 2377 2232 2376 2225 2086 2085 2233 2377 94 2226 2087 2086 2378 2379 97 2227 2088 2087 2234 2236 1951 2088 2374 2230 2380 2235 2379 2230 2090 1946 2237 2380 2381 1946 2089 1945 2237 90 88 2231 2092 1945 94 2234 2233 2232 2093 2092 2102 2243 2101 2101 2242 2238 1820 2096 89 2094 2234 1951 2382 2239 2238 1950 1951 2236 2383 2240 2239 87 1950 2235 2240 2384 2241 88 87 2237 2241 2385 2244 88 90 89 2386 2242 2387 2102 91 2243 2249 2108 2388 2245 2249 2389 2244 2103 2241 2238 2242 2382 2246 2389 2390 2239 2382 2383 2391 2247 2390 2384 2240 2383 2392 2248 2391 2385 2241 2384 2389 2249 2393 2108 2244 2388 2252 2250 1957 2394 2395 2396 2248 1964 2107 2389 2246 2245 2397 2251 2250 2246 2390 2247 2251 2398 2253 2247 2391 2248 2395 2252 2399 1956 1955 2392 2400 2113 2401 2254 2400 2402 2251 2253 2111 2397 2250 2252 2400 2403 2402 2397 2398 2251 2256 2257 2115 2253 2401 2113 2113 2400 2254 2256 2404 2405 1969 2114 1970 2114 2254 2402 2118 2258 2406 2258 1973 2116 2117 2115 2257 2258 2257 2407 2118 1973 2258 1974 1689 2119 2408 1691 1690 1685 1691 2408 2119 2262 2120 2262 1691 2409 2410 2411 2412 2409 1842 2263 2413 2414 2415 1844 2263 1842 2415 2416 2417 1844 1843 1980 1983 2125 2265 1980 1979 2126 1986 1983 2264 2124 2126 1979 1984 2267 2129 2265 2125 2124 2418 2419 2420 2264 1983 2265 2421 2422 2419 1986 2264 2267 2131 2270 2269 1986 2267 1984 2423 2273 2133 1984 2129 2128 2424 2425 2426 2128 2127 2130 2134 1991 2275 2131 2269 2130 2278 2134 2277 2270 2133 2269 2427 2428 558 2423 2133 2270 557 666 567 2273 2423 2274 2429 2280 566 2275 1991 2274 2430 2431 2432 2134 2275 2277 2281 2140 2282 2278 2277 2279 2433 2138 2432 1992 2279 705 2434 2283 2433 1992 705 661 2435 2284 2434 661 698 659 2436 2437 2287 659 708 2136 2285 2438 2144 2280 2137 2136 2438 2146 2288 2137 2281 2282 2439 2145 2286 2282 2140 2139 2440 2289 2439 2139 2138 2141 2441 2290 2440 2141 2283 2142 2442 2291 2441 2284 2143 2142 2443 2292 2442 2285 2144 2143 2444 2293 2443 2438 2288 2144 2445 2446 2447 2146 2001 2288 2447 2448 2297 2145 2000 2001 2295 2449 2154 2289 2148 2000 2449 2156 2298 2148 2290 2149 2450 2155 2296 2149 2291 2150 2451 2299 2450 2150 2292 2151 2452 2300 2451 2293 2152 2151 2453 2301 2452 2294 2153 2152 2454 2455 2456 2295 2154 2153 2302 2304 2018 2154 2449 2298 2457 2303 2456 2298 2156 2012 2458 2305 2457 2012 2155 2010 2305 2459 2163 2010 2299 2158 2459 2307 2165 2159 2158 2300 2460 2309 2306 2159 2301 2160 2309 2168 2310 2018 2160 2302 2461 2166 2462 2016 2018 2304 2166 2463 2169 2162 2016 2303 2463 2312 2170 2163 2162 2305 2312 2464 2171 2165 2163 2459 2464 2315 2317 2307 2164 2165 2315 2319 2029 2309 2310 2164 2465 2318 2466 2168 2167 2310 2318 2467 2320 2166 2169 2167 2467 2321 2032 2169 2463 2170 2322 2468 2469 2312 2171 2170 2322 2470 2323 2171 2464 2317 2470 2471 2324 2317 2315 2029 2471 2472 2325 2027 2029 2319 2472 2473 2326 2320 2027 2318 2473 2474 2327 2320 2467 2032 2178 2328 2474 2032 2321 2033 2178 2475 2329 2323 2033 2322 2475 2476 2330 2324 2323 2470 2476 2477 2331 2325 2324 2471 2477 2478 2332 2326 2325 2472 2478 2479 2333 2327 2326 2473 2479 2480 2334 2328 2327 2474 2480 2481 2335 2178 2329 2328 2481 2482 2336 2475 2330 2329 2482 2483 2337 2476 2331 2330 2483 2484 2338 2477 2332 2331 2484 2485 2339 2478 2333 2332 2485 2486 2340 2479 2334 2333 2486 2341 2053 2480 2335 2334 2487 2488 2489 2336 2335 2481 2342 2490 2343 2337 2336 2482 2490 2491 2344 2338 2337 2483 2491 2199 2345 2339 2338 2484 2492 2197 2493 2339 2485 2340 2197 2346 2201 2340 2486 2053 2494 2495 2496 2341 2054 2053 2347 2497 2203 2054 2342 2343 2497 2498 2204 2490 2344 2343 2498 2349 2205 2491 2345 2344 2499 2500 2501 2199 2198 2345 2351 2353 2208 2197 2201 2198 2502 2352 2501 2202 2201 2346 2352 2211 2354 2347 2203 2202 2503 2209 2504 2204 2203 2497 2505 2355 2503 2205 2204 2498 2355 2506 2213 2205 2349 2206 2506 2357 2074 2208 2206 2351 2507 2359 2356 2207 2208 2353 2508 2360 2507 2207 2352 2354 2361 2508 2509 2354 2211 2210 2361 2510 2217 2210 2209 2212 2510 2219 2364 2212 2355 2213 2511 2218 2362 2213 2506 2074 2512 2365 2511 2074 2357 2072 2513 2366 2512 2072 2359 2215 2514 2367 2513 2360 2216 2215 2515 2368 2514 2361 2217 2216 2516 2369 2515 2510 2364 2217 2517 2370 2516 2219 2080 2364 2518 2519 2373 2218 2079 2080 2371 2520 2227 2365 2221 2079 2520 2229 2374 2221 2366 2222 2521 2228 2372 2222 2367 2223 2522 2375 2521 2223 2368 2224 2523 2376 2522 2224 2369 2225 2524 2377 2523 2370 2226 2225 92 95 97 2371 2227 2226 94 93 2234 2520 2374 2227 93 2379 2236 2374 2229 2090 2525 2380 2378 2090 2228 2089 2526 2527 2528 2089 2375 2231 2381 1812 90 2232 2231 2376 1813 2528 109 2233 2232 2377 2243 2387 2242 2386 2382 2242 2102 89 91 2234 93 2236 2382 2529 2383 2235 2236 2379 2383 2530 2384 2235 2380 2237 2531 2385 2384 90 2237 2381 2385 2532 2388 1812 91 90 104 2386 105 2243 1813 2387 2393 2249 2533 2389 2393 2534 2388 2244 2385 2529 2382 2386 2535 2390 2534 2383 2529 2530 2391 2535 2536 2384 2530 2531 2537 2392 2536 2532 2385 2531 2534 2393 2098 2533 2249 2388 1956 2399 2252 2252 2395 2397 2392 1955 2248 2389 2534 2390 2397 2538 2398 2390 2535 2391 2398 2539 2401 2391 2536 2392 2400 2540 2403 1956 2537 2399 2402 2403 2541 2541 2404 2255 2398 2401 2253 2538 2397 2395 2403 2542 2541 2539 2398 2538 2402 2255 2114 2400 2401 2540 2256 2405 2407 2405 2543 2544 2114 2255 2115 2255 2402 2541 1690 2406 2545 2258 2407 2406 2257 2256 2407 2406 2407 2546 2118 2406 1690 1689 1691 2262 1686 1685 2408 1687 2547 1685 2262 2409 2263 1685 2548 2409 2549 2550 1843 2549 1842 2548 2550 2551 1979 1842 2549 1843 2265 2124 2552 1979 1843 2550 2553 2554 2555 1979 2551 2124 2556 2554 2557 2552 2124 2551 2129 2558 2420 2266 2265 2552 2127 2420 2422 2264 2266 2268 2422 2271 2131 2558 2267 2268 2559 2560 2561 2267 2558 2129 2425 2274 2423 2129 2420 2127 2275 2274 2424 2127 2422 2131 2562 2563 2564 2271 2270 2131 2279 2277 2427 2272 2423 2270 705 2279 558 2272 2425 2423 567 566 708 2425 2424 2274 566 2565 2429 2276 2275 2424 2429 2430 2281 2277 2276 2427 2430 2432 2140 558 2279 2427 2432 2566 2433 705 558 557 2433 2567 2434 705 557 698 2437 2568 2569 698 567 708 2435 2436 2285 708 566 2280 2436 2287 2438 2280 2429 2281 2287 2570 2286 2281 2430 2140 2286 2571 2439 2140 2432 2138 2439 2572 2440 2138 2433 2283 2440 2573 2441 2283 2434 2284 2441 2574 2442 2435 2285 2284 2442 2575 2443 2436 2438 2285 2446 2576 2577 2287 2146 2438 2444 2445 2294 2286 2145 2146 2445 2447 2295 2439 2289 2145 2447 2297 2449 2289 2440 2290 2297 2578 2296 2290 2441 2291 2296 2579 2450 2291 2442 2292 2450 2580 2451 2292 2443 2293 2451 2581 2452 2444 2294 2293 2455 2582 2583 2445 2295 2294 2453 2454 2302 2447 2449 2295 2454 2456 2304 2449 2297 2156 2456 2584 2457 2156 2296 2155 2457 2585 2458 2155 2450 2299 2458 2308 2459 2300 2299 2451 2308 2586 2306 2301 2300 2452 2306 2587 2460 2301 2453 2302 2460 2462 2168 2304 2302 2454 2462 2588 2461 2303 2304 2456 2461 2313 2463 2457 2305 2303 2313 2589 2311 2459 2305 2458 2311 2316 2464 2308 2307 2459 2316 2590 2314 2306 2309 2307 2314 2466 2319 2460 2168 2309 2591 2592 2593 2462 2166 2168 2465 2594 2467 2461 2463 2166 2594 2468 2321 2463 2313 2312 2595 2596 2597 2311 2464 2312 2469 2598 2470 2464 2316 2315 2598 2599 2471 2315 2314 2319 2599 2600 2472 2318 2319 2466 2600 2601 2473 2467 2318 2465 2601 2179 2474 2321 2467 2594 2602 2180 2603 2321 2468 2322 2180 2602 2475 2470 2322 2469 2602 2604 2476 2471 2470 2598 2604 2605 2477 2472 2471 2599 2605 2606 2478 2473 2472 2600 2606 2607 2479 2474 2473 2601 2607 2608 2480 2178 2474 2179 2608 2609 2481 2180 2475 2178 2609 2610 2482 2602 2476 2475 2610 2611 2483 2604 2477 2476 2611 2612 2484 2605 2478 2477 2612 2613 2485 2606 2479 2478 2613 2614 2486 2607 2480 2479 2614 2615 2341 2608 2481 2480 2615 2487 2342 2482 2481 2609 2487 2489 2490 2483 2482 2610 2489 2616 2491 2484 2483 2611 2616 2493 2199 2485 2484 2612 2493 2617 2492 2485 2613 2486 2492 2618 2346 2486 2614 2341 2618 2494 2347 2615 2342 2341 2494 2496 2497 2342 2487 2490 2496 2350 2498 2490 2489 2491 2350 2619 2348 2616 2199 2491 2348 2499 2351 2493 2197 2199 2499 2501 2353 2492 2346 2197 2620 2621 2622 2347 2346 2618 2502 2504 2211 2494 2497 2347 2504 2620 2503 2498 2497 2496 2623 2624 2625 2349 2498 2350 2505 2358 2506 2351 2349 2348 2358 2623 2356 2353 2351 2499 2356 2626 2507 2352 2353 2501 2507 2627 2508 2352 2502 2211 2628 2629 2630 2211 2504 2209 2509 2363 2510 2355 2209 2503 2363 2628 2362 2355 2505 2506 2362 2631 2511 2506 2358 2357 2511 2632 2512 2357 2356 2359 2512 2633 2513 2359 2507 2360 2513 2634 2514 2360 2508 2361 2514 2635 2515 2509 2510 2361 2636 2637 2638 2363 2219 2510 2519 2636 2639 2362 2218 2219 2517 2518 2371 2511 2365 2218 2518 2373 2520 2365 2512 2366 2373 2640 2372 2366 2513 2367 2372 2641 2521 2367 2514 2368 2521 2642 2522 2368 2515 2369 2522 2643 2523 2369 2516 2370 2523 2644 2524 2517 2371 2370 2524 92 94 2518 2520 2371 92 97 93 2520 2373 2229 97 96 2378 2229 2372 2228 2378 2645 2525 2228 2521 2375 2525 2526 2381 2375 2522 2376 2526 2528 1812 2377 2376 2523 2528 2646 109 2377 2524 94 2387 105 2386 104 2529 2386 2243 91 1813 93 97 2379 2647 2530 2529 2379 2378 2380 2530 2648 2531 2380 2525 2381 2531 2649 2532 1812 2381 2526 2532 2650 2533 1813 1812 2528 104 103 102 109 105 2387 2098 2393 2651 2534 2098 81 2533 2388 2532 2529 104 2647 2535 81 2652 2648 2530 2647 2653 2536 2652 2649 2531 2648 2654 2537 2653 2532 2649 2650 2655 2656 2657 2651 2393 2533 2399 2396 2395 2394 2538 2395 2537 1956 2392 81 2535 2534 2538 2656 2539 2535 2652 2536 2539 2655 2540 2536 2653 2537 2658 2394 2659 2396 2399 2654 2542 2403 2660 2661 2541 2542 2539 2540 2401 2394 2656 2538 2543 2404 2661 2656 2655 2539 2661 2542 2662 2540 2660 2403 2405 2544 2546 2663 2664 2545 2255 2404 2256 2404 2541 2661 2408 2545 2664 2406 2546 2545 2407 2405 2546 2546 2663 2545 1690 2545 2408 1691 1685 2409 2665 2547 1687 2665 2411 2547 2409 2548 1842 2547 2666 2548 2550 2667 2413 2667 2549 2666 2413 2417 2551 2550 2549 2667 2555 2266 2552 2550 2413 2551 2268 2266 2554 2417 2552 2551 2558 2268 2556 2417 2555 2552 2418 2556 2668 2554 2266 2555 2669 2670 2671 2556 2268 2554 2421 2559 2271 2558 2556 2418 2559 2672 2272 2420 2558 2418 2673 2674 2675 2420 2419 2422 2563 2276 2424 2421 2271 2422 2427 2276 2562 2271 2559 2272 2676 2677 2678 2672 2425 2272 2676 685 667 2672 2426 2425 565 2679 2565 2426 2563 2424 2565 2680 2681 2562 2276 2563 2430 2429 2681 2428 2427 2562 2431 2682 2566 558 2428 556 2566 2683 2567 666 557 556 2567 2684 2685 567 666 565 2435 2434 2685 566 565 2565 2436 2435 2568 2681 2429 2565 2437 2686 2570 2430 2681 2431 2570 2687 2571 2432 2431 2566 2571 2688 2572 2433 2566 2567 2572 2689 2573 2434 2567 2685 2573 2690 2574 2435 2685 2568 2691 2692 2693 2568 2437 2436 2577 2691 2694 2437 2570 2287 2444 2443 2695 2570 2571 2286 2445 2444 2576 2439 2571 2572 2446 2696 2448 2440 2572 2573 2448 2697 2578 2441 2573 2574 2578 2698 2579 2442 2574 2575 2579 2699 2580 2443 2575 2695 2580 2700 2581 2444 2695 2576 2581 2701 2702 2576 2446 2445 2453 2452 2702 2446 2448 2447 2454 2453 2582 2297 2448 2578 2455 2703 2584 2296 2578 2579 2584 2704 2585 2450 2579 2580 2705 2706 2707 2451 2580 2581 2308 2458 2708 2702 2452 2581 2586 2705 2587 2582 2453 2702 2709 2710 2711 2454 2582 2455 2462 2460 2712 2584 2456 2455 2588 2709 2713 2585 2457 2584 2313 2461 2713 2585 2708 2458 2589 2714 2715 2586 2308 2708 2316 2311 2715 2586 2587 2306 2590 2716 2717 2587 2712 2460 2466 2314 2717 2712 2588 2462 2465 2466 2718 2588 2713 2461 2594 2465 2592 2713 2589 2313 2468 2594 2591 2311 2589 2715 2469 2468 2719 2715 2590 2316 2598 2469 2595 2314 2590 2717 2599 2598 2597 2466 2717 2718 2600 2599 2720 2592 2465 2718 2601 2600 2721 2591 2594 2592 2179 2601 2722 2719 2468 2591 2180 2179 2723 2595 2469 2719 2724 2725 2726 2597 2598 2595 2604 2602 2727 2720 2599 2597 2605 2604 2725 2721 2600 2720 2606 2605 2724 2722 2601 2721 2607 2728 2608 2723 2179 2722 2608 2729 2609 2723 2603 2180 2730 2731 2732 2603 2727 2602 2610 2609 2733 2727 2725 2604 2611 2610 2734 2725 2724 2605 2612 2611 2735 2724 2736 2606 2613 2612 2737 2736 2728 2607 2614 2613 2738 2728 2729 2608 2615 2614 2739 2729 2733 2609 2487 2615 2740 2733 2734 2610 2488 2741 2742 2735 2611 2734 2616 2489 2742 2737 2612 2735 2493 2616 2743 2738 2613 2737 2744 2745 2746 2614 2738 2739 2618 2492 2747 2615 2739 2740 2494 2618 2748 2487 2740 2488 2495 2749 2750 2489 2488 2742 2350 2496 2750 2616 2742 2743 2619 2751 2752 2743 2617 2493 2499 2348 2752 2492 2617 2747 2500 2753 2754 2747 2748 2618 2502 2501 2754 2495 2494 2748 2504 2502 2621 2495 2750 2496 2620 2755 2756 2619 2350 2750 2505 2503 2756 2752 2348 2619 2358 2505 2624 2500 2499 2752 2623 2757 2626 2754 2501 2500 2626 2758 2627 2621 2502 2754 2630 2759 2760 2504 2621 2620 2509 2508 2761 2503 2620 2756 2363 2509 2629 2624 2505 2756 2628 2762 2631 2358 2624 2623 2631 2763 2632 2356 2623 2626 2632 2764 2633 2507 2626 2627 2633 2765 2634 2508 2627 2761 2634 2766 2635 2509 2761 2629 2638 2767 2768 2629 2628 2363 2516 2515 2769 2628 2631 2362 2517 2516 2637 2631 2632 2511 2518 2517 2636 2512 2632 2633 2519 2770 2640 2513 2633 2634 2640 2771 2641 2514 2634 2635 2641 2772 2642 2515 2635 2769 2642 2773 2643 2516 2769 2637 2643 2774 2644 2517 2637 2636 2775 2776 2777 2636 2519 2518 92 2524 2778 2373 2519 2640 95 2775 96 2372 2640 2641 96 2779 2645 2521 2641 2642 2645 2780 2781 2522 2642 2643 2526 2525 2781 2644 2523 2643 2527 2782 2646 2778 2524 2644 2646 2783 110 92 2778 95 2784 123 2785 102 2647 104 2387 1813 109 2378 96 2645 2647 2786 2648 2525 2645 2781 2787 2649 2648 2527 2526 2781 2649 2788 2650 2646 2528 2527 2650 2789 2651 2646 110 109 112 102 101 105 110 103 82 2098 2790 2791 2792 2793 2651 2533 2650 2647 102 2786 2652 80 2794 2648 2786 2787 2653 2794 2795 2788 2649 2787 2791 2654 2795 2789 2650 2788 80 82 2796 2790 2098 2651 2396 2659 2394 2394 2658 2656 2654 2399 2537 80 2652 81 2797 2798 2662 2794 2653 2652 2655 2799 2660 2653 2795 2654 2658 2800 2801 2396 2791 2659 2662 2542 2802 2661 2662 2803 2655 2660 2540 2657 2656 2658 2804 2543 2803 2657 2799 2655 2805 2663 2544 2660 2802 2542 2805 2806 2807 2808 2664 2809 2404 2543 2405 2543 2661 2803 2805 2544 2804 1687 1686 2664 2546 2544 2663 2663 2809 2664 2408 2664 1686 1685 2547 2548 2412 2411 2665 2810 2811 2812 2548 2666 2549 2411 2813 2666 2812 2814 2815 2813 2414 2667 2816 2817 2818 2413 2667 2414 2819 2820 2816 2413 2415 2417 2821 2822 2823 2417 2416 2555 2824 2825 2826 2553 2555 2416 2419 2827 2670 2557 2554 2553 2670 2560 2421 2668 2556 2557 2828 2829 2830 2827 2418 2668 2561 2673 2672 2418 2827 2419 2831 2563 2426 2419 2670 2421 2832 2564 2831 2421 2560 2559 2677 2428 2562 2561 2672 2559 556 2428 2676 2672 2673 2426 666 670 565 2426 2673 2831 700 2680 2679 2564 2563 2831 2833 2834 2835 2677 2562 2564 2681 2836 2431 2676 2428 2677 2835 2683 2682 556 2676 667 2837 2684 2683 670 666 667 2838 2839 2840 565 670 2679 2685 2841 2568 2680 2565 2679 2569 2840 2686 2836 2681 2680 2842 2687 2686 2682 2431 2836 2843 2688 2687 2566 2682 2683 2844 2689 2688 2567 2683 2684 2845 2690 2689 2685 2684 2841 2846 2847 2693 2568 2841 2569 2574 2848 2575 2569 2686 2437 2575 2692 2695 2686 2687 2570 2695 2691 2576 2571 2687 2688 2577 2849 2696 2572 2688 2689 2850 2697 2696 2573 2689 2690 2851 2698 2697 2574 2690 2848 2852 2699 2698 2575 2848 2692 2853 2700 2699 2695 2692 2691 2854 2701 2700 2576 2691 2577 2855 2856 2857 2446 2577 2696 2702 2858 2582 2448 2696 2697 2583 2857 2703 2578 2697 2698 2859 2704 2703 2579 2698 2699 2860 2861 2704 2580 2699 2700 2585 2861 2708 2581 2700 2701 2708 2706 2586 2858 2702 2701 2862 2863 2705 2583 2582 2858 2587 2863 2712 2455 2583 2703 2712 2710 2588 2704 2584 2703 2864 2865 2866 2861 2585 2704 2713 2867 2589 2861 2706 2708 2866 2868 2714 2705 2586 2706 2715 2868 2590 2705 2863 2587 2869 2870 2871 2863 2710 2712 2717 2872 2718 2710 2709 2588 2718 2873 2592 2713 2709 2867 2593 2874 2875 2867 2714 2589 2591 2875 2719 2715 2714 2868 2719 2876 2595 2590 2868 2716 2877 2878 2879 2717 2716 2872 2597 2880 2720 2718 2872 2873 2720 2881 2721 2593 2592 2873 2721 2882 2722 2875 2591 2593 2722 2883 2723 2876 2719 2875 2723 2884 2603 2876 2596 2595 2727 2603 2885 2596 2880 2597 2725 2727 2886 2881 2720 2880 2887 2736 2724 2882 2721 2881 2888 2728 2736 2883 2722 2882 2607 2606 2736 2883 2884 2723 2729 2728 2889 2603 2884 2885 2733 2729 2890 2727 2885 2886 2734 2733 2891 2886 2726 2725 2734 2892 2735 2726 2887 2724 2735 2893 2737 2887 2888 2736 2737 2894 2738 2888 2889 2728 2738 2895 2739 2889 2890 2729 2739 2896 2740 2890 2891 2733 2740 2897 2488 2891 2892 2734 2898 2899 2900 2893 2735 2892 2742 2901 2743 2894 2737 2893 2743 2902 2617 2895 2738 2894 2617 2903 2747 2739 2895 2896 2747 2745 2748 2740 2896 2897 2748 2744 2495 2488 2897 2741 2904 2905 2749 2742 2741 2901 2750 2905 2619 2743 2901 2902 2906 2907 2751 2902 2903 2617 2752 2907 2500 2747 2903 2745 2908 2909 2753 2745 2744 2748 2754 2909 2621 2744 2749 2495 2622 2910 2755 2749 2905 2750 2911 2912 2755 2751 2619 2905 2756 2912 2624 2751 2907 2752 2625 2913 2757 2753 2500 2907 2914 2758 2757 2909 2754 2753 2915 2916 2760 2622 2621 2909 2627 2917 2761 2620 2622 2755 2761 2759 2629 2912 2756 2755 2630 2918 2762 2625 2624 2912 2919 2763 2762 2623 2625 2757 2920 2764 2763 2626 2757 2758 2921 2765 2764 2627 2758 2917 2922 2923 2924 2761 2917 2759 2924 2925 2768 2629 2759 2630 2635 2926 2769 2630 2762 2628 2769 2767 2637 2631 2762 2763 2638 2927 2639 2632 2763 2764 2639 2928 2770 2633 2764 2765 2929 2771 2770 2634 2765 2766 2930 2772 2771 2635 2766 2926 2931 2773 2772 2769 2926 2767 2932 2774 2773 2637 2767 2638 2933 2934 2777 2636 2638 2639 2644 2935 2778 2639 2770 2519 2778 2776 95 2640 2770 2771 2936 2779 2775 2641 2771 2772 2937 2780 2779 2642 2772 2773 2938 2939 2940 2643 2773 2774 2781 2941 2527 2935 2644 2774 2782 2940 2783 2776 2778 2935 2942 2943 111 2775 95 2776 110 2944 103 2775 2779 96 112 2786 102 2645 2779 2780 134 2787 2786 2941 2781 2780 2787 2945 2788 2782 2527 2941 2788 2946 2789 2646 2782 2783 2789 2947 2790 2944 110 2783 119 112 111 101 103 2944 2796 82 2948 80 2796 2949 2790 2651 2789 2786 112 134 2950 2794 2949 2945 2787 134 2792 2795 2950 2788 2945 2946 2801 2951 2952 2947 2789 2946 2949 2796 2953 2948 82 2790 2659 2800 2658 2801 2657 2658 2791 2396 2654 80 2949 2794 2657 2952 2799 2794 2950 2795 2799 2954 2802 2795 2792 2791 2951 2801 2955 2659 2793 2800 2803 2798 2956 2956 2806 2804 2799 2802 2660 2952 2657 2801 2798 2957 2956 2954 2799 2952 2807 2809 2805 2802 2797 2662 2662 2798 2803 2807 2958 2959 2543 2804 2544 2804 2803 2956 2808 2960 2961 2808 1687 2664 2663 2805 2809 2808 2809 2960 2665 1687 2808 2547 2411 2666 2261 2410 2412 2260 2410 2261 2666 2813 2667 2410 2962 2813 2963 2817 2415 2963 2414 2962 2817 2820 2416 2414 2963 2415 2823 2557 2553 2415 2817 2416 2668 2557 2822 2820 2553 2416 2827 2668 2964 2820 2823 2553 2965 2825 2966 2822 2557 2823 2560 2669 2829 2964 2668 2822 2829 2674 2561 2671 2827 2964 2967 2968 2969 2827 2671 2670 2970 2969 2971 2670 2669 2560 2972 2677 2564 2560 2829 2561 2973 2678 2972 2674 2673 2561 664 2974 676 2673 2675 2831 670 701 2679 2675 2832 2831 2975 2976 700 2832 2972 2564 2680 2976 2836 2678 2677 2972 2836 2833 2682 685 2676 2678 2835 2977 2837 671 667 685 2978 2979 2839 701 670 671 2684 2980 2841 2679 701 700 2841 2838 2569 2976 2680 700 2840 2981 2842 2833 2836 2976 2982 2843 2842 2835 2682 2833 2983 2844 2843 2683 2835 2837 2984 2985 2986 2684 2837 2980 2986 2987 2847 2841 2980 2838 2690 2988 2848 2569 2838 2840 2848 2846 2692 2686 2840 2842 2693 2989 2694 2687 2842 2843 2694 2990 2849 2688 2843 2844 2849 2991 2850 2689 2844 2845 2850 2992 2851 2690 2845 2988 2993 2852 2851 2848 2988 2846 2994 2853 2852 2692 2846 2693 2995 2854 2853 2691 2693 2694 2996 2997 2856 2577 2694 2849 2701 2998 2858 2696 2849 2850 2858 2855 2583 2697 2850 2851 2857 2999 2859 2698 2851 2852 3000 2860 2859 2699 2852 2853 3001 3002 3003 2700 2853 2854 2861 3004 2706 2998 2701 2854 2707 3003 2862 2855 2858 2998 3005 3006 2862 2857 2583 2855 2863 3006 2710 2859 2703 2857 2711 3007 3008 2860 2704 2859 2709 3008 2867 3004 2861 2860 2867 2864 2714 3004 2707 2706 3009 3010 3011 2862 2705 2707 2868 3012 2716 2862 3006 2863 2716 3013 2872 3006 2711 2710 2872 2869 2873 2711 3008 2709 2873 2871 2593 2867 3008 2864 2874 3014 3015 2864 2866 2714 2875 3015 2876 2868 2866 3012 2876 3016 2596 2716 3012 3013 2880 2596 3017 2872 3013 2869 2880 2878 2881 2873 2869 2871 2881 2877 2882 2874 2593 2871 2882 3018 2883 3015 2875 2874 2883 3019 2884 3016 2876 3015 2884 3020 2885 3016 3017 2596 2886 2885 3021 3017 2878 2880 2726 2886 3022 2878 2877 2881 2887 2726 3023 2877 3018 2882 2888 2887 3024 3018 3019 2883 2889 2888 3025 3019 3020 2884 2890 2889 3026 2885 3020 3021 2891 2890 3027 2886 3021 3022 2892 2891 3028 2726 3022 3023 2893 2892 3029 3023 3024 2887 2893 3030 2894 3024 3025 2888 2894 3031 2895 3025 3026 2889 2895 3032 2896 3026 3027 2890 2896 3033 2897 3027 3028 2891 2897 3034 2741 3028 3029 2892 2741 3035 2901 3030 2893 3029 2901 2898 2902 3031 2894 3030 2902 2900 2903 3032 2895 3031 2903 3036 2745 3033 2896 3032 2746 3037 3038 2897 3033 3034 2744 3038 2749 2741 3034 3035 3039 3040 3041 2901 3035 2898 2905 3042 2751 2902 2898 2900 3043 3044 3045 2900 3036 2903 2907 3046 2753 2745 3036 2746 3045 3047 2908 2746 3038 2744 2909 3047 2622 3038 2904 2749 2910 3048 2911 2904 3042 2905 3049 3050 3051 2906 2751 3042 2912 3052 2625 2906 3046 2907 2913 3051 2914 2908 2753 3046 3053 3054 2914 3047 2909 2908 2758 3054 2917 2910 2622 3047 2917 2915 2759 2911 2755 2910 2760 3055 2918 3052 2912 2911 2918 3056 2919 2913 2625 3052 3057 2920 2919 2757 2913 2914 3058 2921 2920 2758 2914 3054 3059 3060 2923 2917 3054 2915 2765 3061 2766 2759 2915 2760 2766 2922 2926 2630 2760 2918 2926 2924 2767 2762 2918 2919 2768 3062 2927 2763 2919 2920 2927 3063 2928 2764 2920 2921 2928 3064 2929 2765 2921 3061 3065 2930 2929 2766 3061 2922 3066 2931 2930 2926 2922 2924 3067 2932 2931 2767 2924 2768 3068 3069 2934 2638 2768 2927 2774 3070 2935 2639 2927 2928 2935 2933 2776 2770 2928 2929 2777 3071 2936 2771 2929 2930 2936 3072 2937 2772 2930 2931 3073 3074 2937 2773 2931 2932 2780 3074 2941 2774 2932 3070 2941 2938 2782 2933 2935 3070 2940 3075 3076 2777 2776 2933 2783 3076 2944 2936 2775 2777 2944 2942 101 2937 2779 2936 3077 119 111 2780 2937 3074 121 2945 134 2938 2941 3074 3078 2946 2945 2940 2782 2938 2946 3079 2947 3076 2783 2940 2947 3080 2948 2942 2944 3076 119 3077 120 101 2942 111 2953 2796 3081 2949 2953 3082 2948 2790 2947 134 119 121 2950 3082 98 2945 121 3078 3083 2792 98 3079 2946 3078 3084 2793 3083 3080 2947 3079 3085 3082 2953 2948 3081 2796 2800 2955 2801 3086 3087 3088 2793 2659 2791 3082 2950 2949 3089 2954 2952 2950 98 2792 2954 3090 2797 2792 3083 2793 2951 3091 3087 2800 3084 2955 2957 2798 3092 3093 2956 2957 2954 2797 2802 3089 2952 2951 2958 2806 3093 3089 3090 2954 3093 2957 3094 2797 3092 2798 2807 2959 2960 2959 3095 3096 2804 2806 2805 2806 2956 3093 2412 2961 3097 2961 2665 2808 2809 2807 2960 2961 2960 3098 2412 2665 2961 2410 2813 2411 3099 2260 2259 3099 2814 2260 2813 2962 2414 2260 3100 2962 3101 3102 3103 2818 2963 3100 3104 3105 3106 2817 2963 2818 3107 3108 3104 2817 2816 2820 2826 2964 2822 2820 2819 2823 2671 2964 2825 2821 2823 2819 2669 2965 2830 2821 2826 2822 3109 3110 3111 2825 2964 2826 2828 2967 2674 2671 2825 2965 2967 2970 2675 2671 2965 2669 3112 2972 2832 2669 2830 2829 3113 3114 3115 2828 2674 2829 685 2678 2974 2967 2675 2674 671 663 701 2675 2970 2832 699 3116 2975 2970 3112 2832 3117 3118 3119 2973 2972 3112 2976 3120 2833 2974 2678 2973 2834 3119 2977 664 685 2974 2977 3121 3122 663 671 664 2837 3122 2980 699 701 663 2980 2978 2838 2975 700 699 2839 3123 2981 3120 2976 2975 2981 3124 2982 2834 2833 3120 3125 2983 2982 2977 2835 2834 3126 3127 2985 2837 2977 3122 2844 3128 2845 2980 3122 2978 2845 2984 2988 2838 2978 2839 2988 2986 2846 2981 2840 2839 2847 3129 2989 2842 2981 2982 2989 3130 2990 2843 2982 2983 2990 3131 2991 2844 2983 3128 2991 3132 2992 2845 3128 2984 2992 3133 2993 2988 2984 2986 3134 2994 2993 2846 2986 2847 3135 2995 2994 2693 2847 2989 3136 3137 2997 2694 2989 2990 2854 3138 2998 2849 2990 2991 2998 2996 2855 2992 2850 2991 2856 3139 2999 2851 2992 2993 2999 3140 3000 2852 2993 2994 3141 3142 3000 2853 2994 2995 2860 3142 3004 2854 2995 3138 3004 3001 2707 2996 2998 3138 3003 3143 3005 2856 2855 2996 3144 3145 3146 2999 2857 2856 3006 3147 2711 3000 2859 2999 3007 3146 3148 3142 2860 3000 3008 3148 2864 3142 3001 3004 2865 3149 3150 3001 3003 2707 2866 3150 3012 3005 2862 3003 3012 3009 3013 3005 3147 3006 3013 3011 2869 2711 3147 3007 2870 3151 3152 3007 3148 3008 2871 3152 2874 2864 3148 2865 3153 3154 3155 2865 3150 2866 3015 3156 3016 3012 3150 3009 3016 3157 3017 3013 3009 3011 2878 3017 3158 2870 2869 3011 2879 3159 3160 2871 2870 3152 2877 3160 3018 3014 2874 3152 3018 3161 3019 3156 3015 3014 3019 3162 3020 3157 3016 3156 3020 3163 3021 3157 3158 3017 3022 3021 3164 3158 2879 2878 3023 3022 3165 2879 3160 2877 3024 3023 3166 3160 3161 3018 3025 3024 3167 3161 3162 3019 3026 3025 3168 3162 3163 3020 3027 3026 3169 3021 3163 3164 3028 3027 3170 3022 3164 3165 3029 3028 3171 3023 3165 3166 3030 3029 3172 3024 3166 3167 3031 3030 3173 3167 3168 3025 3031 3174 3032 3168 3169 3026 3032 3175 3033 3169 3170 3027 3033 3176 3034 3170 3171 3028 3034 3177 3035 3171 3172 3029 3035 3178 2898 3172 3173 3030 2899 3179 3180 3174 3031 3173 2900 3180 3036 3175 3032 3174 3036 3181 2746 3176 3033 3175 3037 3182 3183 3034 3176 3177 3038 3183 2904 3035 3177 3178 2904 3184 3042 2898 3178 2899 3042 3039 2906 2900 2899 3180 2906 3041 3046 3180 3181 3036 3046 3043 2908 2746 3181 3037 3185 3186 3187 3037 3183 3038 3047 3188 2910 3183 3184 2904 3048 3187 3189 3184 3039 3042 2911 3189 3052 3041 2906 3039 3052 3049 2913 3041 3043 3046 3051 3190 3053 3045 2908 3043 3191 3192 3193 3188 3047 3045 3054 3194 2915 3188 3048 2910 2916 3193 3055 3189 2911 3048 3055 3195 3056 3049 3052 3189 3056 3196 3057 3051 2913 3049 3197 3058 3057 2914 3051 3053 3198 3199 3060 3054 3053 3194 2921 3200 3061 2915 3194 2916 3061 3059 2922 3055 2760 2916 2923 3201 2925 3056 2918 3055 2925 3202 3062 2919 3056 3057 3062 3203 3063 2920 3057 3058 3063 3204 3064 2921 3058 3200 3064 3205 3065 3061 3200 3059 3206 3066 3065 2922 3059 2923 3207 3067 3066 2924 2923 2925 3208 3209 3069 2768 2925 3062 2932 3210 3070 2927 3062 3063 3070 3068 2933 3064 2928 3063 2934 3211 3071 3065 2929 3064 3071 3212 3072 2930 3065 3066 3072 3213 3073 2931 3066 3067 3214 3215 3216 2932 3067 3210 3074 3217 2938 3068 3070 3210 2939 3216 3075 2934 2933 3068 3075 3218 3219 3071 2777 2934 3076 3219 2942 3071 3072 2936 2943 3220 3077 3073 2937 3072 3221 3222 123 3074 3073 3217 121 2784 3078 2939 2938 3217 3078 2785 3079 3075 2940 2939 3223 3080 3079 3219 3076 3075 3080 3224 3081 2943 2942 3219 120 3225 3221 2943 3077 111 3085 2953 3226 99 3082 3085 3081 2948 3080 121 120 2784 107 3227 108 3078 2784 2785 3083 100 3228 3079 2785 3223 3229 3084 3228 3224 3080 3223 99 3085 3227 3226 2953 3081 2955 3091 2951 3087 3089 2951 3084 2800 2793 3082 99 98 3089 3230 3090 98 100 3083 3090 3231 3092 3083 3228 3084 2957 3232 3094 2955 3229 3091 3093 3094 3233 3234 3235 3096 3090 3092 2797 3230 3089 3087 3095 2958 3233 3231 3090 3230 3096 3098 2959 3092 3232 2957 3096 3236 3234 3237 3097 3235 2806 2958 2807 2958 3093 3233 2261 3097 3237 2961 3098 3097 2960 2959 3098 3098 3235 3097 2412 3097 2261 2410 2260 2962 2815 2814 3099 3238 3239 3240 2962 3100 2963 3241 3100 2814 3242 3243 2816 3242 2818 3241 3243 3108 2819 2818 3242 2816 3244 2826 2821 2819 2816 3243 3245 3246 3247 2819 3108 2821 3248 3246 3249 3108 3244 2821 2830 3250 3110 2824 2826 3244 3110 2968 2828 2966 2825 2824 3251 2968 3109 3250 2965 2966 3252 3253 3254 2965 3250 2830 3114 2973 3112 3110 2828 2830 2974 2973 3113 2828 2968 2967 675 3255 551 2970 2967 2969 663 668 699 2971 3112 2970 3116 3256 3257 3114 3112 2971 2975 3257 3120 2973 3114 3113 3120 3117 2834 676 2974 3113 3119 3258 3121 676 665 664 3259 3260 3261 668 663 665 3122 3262 2978 668 3116 699 2979 3259 3123 3257 2975 3116 3123 3263 3124 3117 3120 3257 3124 3264 3125 3119 2834 3117 3265 3266 3127 3121 2977 3119 2983 3267 3128 3122 3121 3262 3128 3126 2984 2979 2978 3262 2985 3268 2987 3123 2839 2979 2987 3269 3129 3124 2981 3123 3129 3270 3130 3125 2982 3124 3130 3271 3131 2983 3125 3267 3131 3272 3132 3128 3267 3126 3132 3273 3133 2984 3126 2985 3133 3274 3134 2986 2985 2987 3275 3276 3277 2847 2987 3129 3277 3278 3137 2989 3129 3130 2995 3279 3138 2990 3130 3131 3138 3136 2996 3132 2991 3131 2997 3280 3139 3133 2992 3132 3139 3281 3140 2993 3133 3134 3140 3282 3141 2994 3134 3135 3283 3284 3285 2995 3135 3279 3142 3286 3001 3136 3138 3279 3002 3285 3143 2997 2996 3136 3143 3287 3288 3139 2856 2997 3005 3288 3147 3140 2999 3139 3147 3144 3007 3141 3000 3140 3146 3289 3290 3286 3142 3141 3148 3290 2865 3286 3002 3001 3149 3291 3292 3002 3143 3003 3150 3292 3009 3143 3288 3005 3010 3293 3294 3288 3144 3147 3011 3294 2870 3007 3144 3146 3151 3295 3296 3146 3290 3148 3152 3296 3014 2865 3290 3149 3156 3014 3297 3149 3292 3150 3156 3154 3157 3009 3292 3010 3157 3153 3158 3011 3010 3294 2879 3158 3298 3151 2870 3294 3299 3300 3301 3152 3151 3296 3160 3302 3161 3297 3014 3296 3161 3303 3162 3154 3156 3297 3162 3304 3163 3153 3157 3154 3163 3305 3164 3153 3298 3158 3165 3164 3306 3298 3159 2879 3166 3165 3307 3159 3302 3160 3167 3166 3308 3302 3303 3161 3168 3167 3309 3303 3304 3162 3169 3168 3310 3304 3305 3163 3170 3169 3311 3164 3305 3306 3171 3170 3312 3165 3306 3307 3172 3171 3313 3166 3307 3308 3173 3172 3314 3167 3308 3309 3174 3173 3315 3168 3309 3310 3175 3174 3316 3310 3311 3169 3175 2730 3176 3311 3312 3170 3176 2732 3177 3312 3313 3171 3177 3317 3178 3313 3314 3172 3178 3318 2899 3314 3315 3173 3319 3320 3321 3316 3174 3315 3180 3322 3181 2730 3175 3316 3181 3323 3037 2732 3176 2730 3324 3325 3326 3177 2732 3317 3183 3327 3184 3178 3317 3318 3184 3328 3039 3179 2899 3318 3040 3329 3330 3180 3179 3322 3041 3330 3043 3181 3322 3323 3044 3331 3332 3037 3323 3182 3045 3332 3188 3182 3327 3183 3188 3185 3048 3327 3328 3184 3187 3333 3334 3328 3040 3039 3189 3334 3049 3040 3330 3041 3050 3335 3190 3330 3044 3043 3190 3336 3337 3332 3045 3044 3053 3337 3194 3185 3188 3332 3194 3191 2916 3185 3187 3048 3193 3338 3195 3334 3189 3187 3195 3339 3196 3050 3049 3334 3196 3340 3197 3190 3051 3050 3341 3342 3199 3053 3190 3337 3058 3343 3200 3194 3337 3191 3200 3198 3059 3193 2916 3191 3060 3344 3201 3195 3055 3193 3201 3345 3202 3196 3056 3195 3202 3346 3203 3057 3196 3197 3203 3347 3204 3058 3197 3343 3204 3348 3205 3200 3343 3198 3205 3349 3206 3059 3198 3060 3206 3350 3207 2923 3060 3201 3351 3352 3209 2925 3201 3202 3067 3353 3210 3062 3202 3203 3210 3208 3068 3204 3063 3203 3069 3354 3211 3205 3064 3204 3211 3355 3212 3206 3065 3205 3212 3356 3213 3066 3206 3207 3213 3357 3358 3067 3207 3353 3073 3358 3217 3210 3353 3208 3217 3214 2939 3069 3068 3208 3216 3359 3218 3211 2934 3069 3360 3361 3362 3212 3071 3211 3219 3363 2943 3212 3213 3072 3220 3360 3225 3358 3073 3213 120 3077 3225 3214 3217 3358 3221 2784 120 2939 3214 3216 2785 116 3223 3218 3075 3216 3223 118 3224 3363 3219 3218 3224 3364 3226 3220 2943 3363 3365 3222 3221 3220 3225 3077 3227 3085 3366 99 3227 107 3226 3081 3224 2784 3221 123 3367 100 107 116 2785 123 3368 3228 3367 118 3223 116 3369 3229 3368 3224 118 3364 3370 3371 3372 3366 3085 3226 3091 3088 3087 3086 3230 3087 3229 2955 3084 99 107 100 3371 3231 3230 100 3367 3228 3231 3370 3232 3228 3368 3229 3373 3086 3374 3088 3091 3369 3375 3094 3376 3377 3233 3375 3231 3232 3092 3371 3230 3086 3236 3095 3377 3371 3370 3231 3377 3375 3378 3376 3094 3232 3094 3375 3233 3234 3379 3380 2958 3095 2959 3095 3233 3377 3237 3381 3382 2259 2261 3237 3098 3096 3235 3237 3235 3381 3099 2259 3237 2260 2814 3100 2810 2812 2815 2811 3102 2812 3100 3241 2818 2812 3383 3241 3243 3384 3104 3384 3242 3383 3385 3386 3387 3243 3242 3384 3247 2824 3244 3243 3104 3108 2966 2824 3246 3108 3107 3244 3250 2966 3248 3107 3247 3244 3388 3389 3390 3246 2824 3247 3391 3392 3393 3248 2966 3246 3251 3252 2969 3250 3248 3111 3252 3394 2971 3250 3111 3110 3395 3396 3397 3110 3109 2968 3255 676 3113 3251 2969 2968 3398 553 674 2971 2969 3252 668 3399 3116 3114 2971 3394 3256 561 3400 3394 3115 3114 3257 3400 3117 3113 3115 3255 3118 3401 3258 676 3255 675 3258 3402 3403 675 669 665 3262 3121 3403 3399 668 669 3262 3260 2979 3399 3256 3116 3259 3404 3263 3256 3400 3257 3263 3405 3264 3118 3117 3400 3406 3266 3407 3258 3119 3118 3267 3125 3408 3403 3121 3258 3267 3265 3126 3260 3262 3403 3127 3409 3268 3259 2979 3260 3268 3410 3269 3263 3123 3259 3269 3411 3270 3264 3124 3263 3270 3412 3271 3408 3125 3264 3271 3413 3272 3267 3408 3265 3272 3414 3273 3126 3265 3127 3273 3415 3274 2985 3127 3268 3416 3276 3417 2987 3268 3269 3134 3418 3135 3129 3269 3270 3135 3275 3279 3130 3270 3271 3279 3277 3136 3272 3131 3271 3137 3419 3280 3273 3132 3272 3280 3420 3281 3274 3133 3273 3281 3421 3282 3418 3134 3274 3422 3284 3423 3135 3418 3275 3141 3424 3286 3279 3275 3277 3286 3283 3002 3137 3136 3277 3285 3425 3287 3280 2997 3137 3426 3427 3428 3281 3139 3280 3288 3429 3144 3281 3282 3140 3145 3426 3289 3424 3141 3282 3430 3431 3432 3283 3286 3424 3290 3433 3149 3283 3285 3002 3291 3430 3434 3285 3287 3143 3292 3434 3010 3287 3429 3288 3293 3435 3436 3429 3145 3144 3294 3436 3151 3146 3145 3289 3437 3438 3439 3289 3433 3290 3296 3440 3297 3149 3433 3291 3154 3297 3441 3292 3291 3434 3155 3442 3443 3010 3434 3293 3153 3443 3298 3294 3293 3436 3159 3298 3444 3295 3151 3436 3302 3159 3445 3296 3295 3440 3302 3300 3303 3441 3297 3440 3303 3299 3304 3155 3154 3441 3304 3446 3305 3443 3153 3155 3305 3447 3306 3443 3444 3298 3307 3306 3448 3444 3445 3159 3308 3307 3449 3445 3300 3302 3309 3308 3450 3300 3299 3303 3310 3309 3451 3299 3446 3304 3311 3310 3452 3446 3447 3305 3312 3311 3453 3306 3447 3448 3313 3312 3454 3307 3448 3449 3314 3313 3455 3308 3449 3450 3315 3314 3456 3309 3450 3451 3316 3315 3457 3310 3451 3452 2730 3316 3458 3311 3452 3453 3459 3460 3461 3453 3454 3312 2732 3462 3317 3454 3455 3313 3317 3463 3318 3455 3456 3314 3318 3464 3179 3456 3457 3315 3322 3179 3465 3458 3316 3457 3322 3320 3323 2731 2730 3458 3323 3319 3182 3462 2732 2731 3327 3182 3466 3317 3462 3463 3327 3325 3328 3464 3318 3463 3328 3324 3040 3465 3179 3464 3329 3467 3468 3322 3465 3320 3330 3468 3044 3323 3320 3319 3331 3469 3470 3182 3319 3466 3332 3470 3185 3327 3466 3325 3186 3471 3333 3328 3325 3324 3472 3473 3474 3324 3329 3040 3334 3475 3050 3329 3468 3330 3335 3472 3336 3468 3331 3044 3476 3477 3478 3470 3332 3331 3337 3479 3191 3470 3186 3185 3192 3476 3338 3186 3333 3187 3338 3480 3339 3475 3334 3333 3339 3481 3340 3335 3050 3475 3342 3482 3483 3336 3190 3335 3197 3484 3343 3337 3336 3479 3343 3341 3198 3192 3191 3479 3199 3485 3344 3338 3193 3192 3344 3486 3345 3339 3195 3338 3345 3487 3346 3340 3196 3339 3346 3488 3347 3197 3340 3484 3347 3489 3348 3343 3484 3341 3348 3490 3349 3198 3341 3199 3491 3492 3493 3060 3199 3344 3352 3492 3494 3201 3344 3345 3207 3495 3353 3202 3345 3346 3353 3351 3208 3347 3203 3346 3209 3496 3354 3348 3204 3347 3354 3497 3355 3349 3205 3348 3355 3498 3356 3350 3206 3349 3356 3499 3357 3207 3350 3495 3500 3501 3502 3353 3495 3351 3358 3503 3214 3209 3208 3351 3215 3500 3359 3354 3069 3209 3359 3504 3505 3355 3211 3354 3363 3218 3505 3356 3212 3355 3363 3361 3220 3356 3357 3213 3360 3506 3365 3503 3358 3357 3221 3225 3365 3503 3215 3214 3222 3507 122 3215 3359 3216 3508 126 128 3359 3505 3218 118 127 3364 3363 3505 3361 3364 3509 3366 3360 3220 3361 3510 3507 3222 3360 3365 3225 108 3227 3511 3512 3513 3514 3366 3226 3364 3222 122 123 3367 106 3515 116 122 117 3516 3368 3515 127 118 117 3517 3369 3516 3509 3364 127 106 108 129 3511 3227 3366 3088 3374 3086 3086 3373 3371 3369 3091 3229 106 3367 107 3376 3370 3518 3367 3515 3368 3519 3520 3521 3368 3516 3369 3373 3513 3512 3088 3517 3374 3378 3375 3522 3377 3378 3521 3370 3376 3232 3372 3371 3373 3379 3236 3521 3518 3370 3372 3521 3378 3519 3376 3522 3375 3234 3380 3381 3380 3523 3524 3095 3236 3096 3236 3377 3521 2815 3382 3525 3382 3099 3237 3235 3234 3381 3382 3381 3526 2815 3099 3382 2812 3241 2814 3103 3102 2811 3527 3528 3529 3241 3383 3242 3102 3530 3383 3531 3527 3532 3105 3384 3530 3106 3533 3107 3104 3384 3105 3534 3535 3387 3107 3104 3106 3536 3537 3538 3107 3533 3247 3111 3248 3389 3245 3247 3533 3109 3388 3392 3249 3246 3245 3392 3253 3251 3389 3248 3249 3539 3540 3541 3111 3389 3388 3254 3395 3394 3111 3388 3109 3542 3255 3115 3109 3392 3251 3543 551 3542 3252 3251 3253 3399 669 3398 3252 3254 3394 3399 559 3256 3394 3395 3115 3544 3545 3546 3395 3542 3115 3118 3400 3547 3542 551 3255 3401 3545 3402 551 553 675 3548 3549 3550 553 3398 669 3260 3403 3551 3398 559 3399 3261 3549 3404 559 561 3256 3404 3552 3405 561 3547 3400 3405 3553 3554 3401 3118 3547 3408 3264 3554 3402 3258 3401 3265 3408 3407 3402 3551 3403 3266 3555 3409 3261 3260 3551 3409 3556 3410 3404 3259 3261 3410 3557 3411 3405 3263 3404 3411 3558 3412 3554 3264 3405 3412 3559 3413 3407 3408 3554 3413 3560 3414 3265 3407 3266 3561 3562 3563 3127 3266 3409 3564 3416 3562 3268 3409 3410 3418 3274 3565 3269 3410 3411 3275 3418 3417 3412 3270 3411 3276 3566 3278 3413 3271 3412 3278 3567 3419 3414 3272 3413 3419 3568 3420 3415 3273 3414 3420 3569 3421 3565 3274 3415 3421 3570 3571 3417 3418 3565 3424 3282 3571 3275 3417 3276 3424 3423 3283 3278 3277 3276 3284 3572 3425 3419 3137 3278 3425 3573 3574 3420 3280 3419 3429 3287 3574 3421 3281 3420 3429 3427 3145 3421 3571 3282 3426 3575 3576 3571 3423 3424 3433 3289 3576 3284 3283 3423 3433 3431 3291 3284 3425 3285 3577 3578 3579 3425 3574 3287 3434 3580 3293 3574 3427 3429 3581 3582 3583 3427 3426 3145 3436 3584 3295 3289 3426 3576 3440 3295 3585 3576 3431 3433 3440 3438 3441 3291 3431 3430 3155 3441 3437 3434 3430 3580 3586 3587 3588 3293 3580 3435 3443 3589 3444 3436 3435 3584 3445 3444 3590 3585 3295 3584 3300 3445 3591 3438 3440 3585 3592 3593 3594 3437 3441 3438 3299 3595 3446 3442 3155 3437 3446 3596 3447 3589 3443 3442 3447 3597 3448 3589 3590 3444 3449 3448 3598 3590 3591 3445 3450 3449 3599 3591 3301 3300 3451 3450 3600 3301 3595 3299 3452 3451 3601 3595 3596 3446 3453 3452 3602 3596 3597 3447 3454 3453 3603 3448 3597 3598 3455 3454 3604 3449 3598 3599 3456 3455 3605 3450 3599 3600 3457 3456 3606 3451 3600 3601 3458 3457 3607 3452 3601 3602 2731 3458 3608 3453 3602 3603 3462 2731 3609 3603 3604 3454 3462 3460 3463 3604 3605 3455 3463 3459 3464 3605 3606 3456 3465 3464 3610 3606 3607 3457 3320 3465 3611 3607 3608 3458 3321 3612 3613 3609 2731 3608 3319 3613 3466 3460 3462 3609 3325 3466 3614 3459 3463 3460 3326 3615 3616 3610 3464 3459 3329 3324 3616 3611 3465 3610 3617 3618 3619 3320 3611 3321 3468 3620 3331 3319 3321 3613 3469 3617 3621 3466 3613 3614 3470 3621 3186 3325 3614 3326 3471 3622 3623 3324 3326 3616 3475 3333 3623 3616 3467 3329 3475 3473 3335 3467 3620 3468 3472 3624 3625 3620 3469 3331 3479 3336 3625 3469 3621 3470 3479 3477 3192 3621 3471 3186 3476 3626 3480 3471 3623 3333 3480 3627 3481 3473 3475 3623 3628 3483 3629 3472 3335 3473 3484 3340 3630 3625 3336 3472 3484 3482 3341 3477 3479 3625 3342 3631 3485 3476 3192 3477 3485 3632 3486 3480 3338 3476 3486 3633 3487 3481 3339 3480 3487 3634 3488 3630 3340 3481 3488 3635 3489 3484 3630 3482 3489 3636 3490 3341 3482 3342 3637 3491 3638 3199 3342 3485 3350 3349 3639 3344 3485 3486 3495 3350 3493 3345 3486 3487 3495 3492 3351 3488 3346 3487 3352 3640 3496 3489 3347 3488 3496 3641 3497 3490 3348 3489 3497 3642 3498 3639 3349 3490 3498 3643 3499 3493 3350 3639 3644 3502 3645 3495 3493 3492 3503 3357 3646 3351 3492 3352 3503 3501 3215 3496 3209 3352 3500 3647 3504 3497 3354 3496 3504 3648 3649 3498 3355 3497 3361 3505 3649 3498 3499 3356 3362 3650 3506 3499 3646 3357 3506 3651 3510 3501 3503 3646 3222 3365 3510 3501 3500 3215 3507 3652 3653 3500 3504 3359 117 122 3653 3504 3649 3505 127 126 3509 3362 3361 3649 3509 125 3511 3362 3506 3360 3507 3654 3652 3510 3365 3506 129 108 3655 106 129 3656 3511 3366 3509 3507 3653 122 3657 3515 3656 128 117 3653 3658 3516 3657 127 128 126 3659 3517 3658 125 3509 126 3656 129 131 3655 108 3511 3374 3513 3373 3512 3372 3373 3517 3088 3369 106 3656 3515 3372 3660 3518 3515 3657 3516 3518 3661 3522 3517 3516 3658 3662 3512 3514 3513 3374 3659 3519 3378 3663 3520 3523 3379 3518 3522 3376 3660 3372 3512 3664 3520 3519 3661 3518 3660 3524 3526 3380 3663 3378 3522 3665 3666 3524 3667 3525 3668 3236 3379 3234 3521 3520 3379 2810 3525 3667 3382 3526 3525 3381 3380 3526 3526 3668 3525 2815 3525 2810 2812 3102 3383 3239 3101 3103 3238 3101 3239 3383 3530 3384 3101 3669 3530 3106 3670 3385 3670 3105 3669 3385 3535 3533 3106 3105 3670 3538 3249 3245 3106 3385 3533 3389 3249 3537 3533 3535 3245 3671 3672 3673 3535 3538 3245 3674 3671 3675 3537 3249 3538 3253 3391 3540 3389 3537 3390 3540 3396 3254 3393 3388 3390 3396 3539 3676 3388 3393 3392 3677 3678 3679 3392 3391 3253 672 678 680 3540 3254 3253 559 3398 673 3254 3396 3395 560 3680 3681 3395 3397 3542 3547 561 3681 3543 3542 3397 3401 3547 3546 3543 552 551 3545 3682 3683 552 674 553 3551 3402 3683 674 673 3398 3261 3551 3550 673 560 559 3549 3684 3552 560 3681 561 3552 3685 3553 3681 3546 3547 3686 3687 3688 3545 3401 3546 3407 3554 3689 3545 3683 3402 3555 3406 3687 3683 3550 3551 3555 3690 3556 3549 3261 3550 3556 3691 3557 3552 3404 3549 3557 3692 3558 3553 3405 3552 3558 3693 3559 3689 3554 3553 3694 3695 3696 3406 3407 3689 3697 3561 3695 3266 3406 3555 3415 3414 3698 3409 3555 3556 3565 3415 3563 3410 3556 3557 3417 3565 3562 3558 3411 3557 3566 3416 3699 3559 3412 3558 3566 3700 3567 3560 3413 3559 3567 3701 3568 3698 3414 3560 3568 3702 3569 3563 3415 3698 3569 3703 3570 3562 3565 3563 3704 3705 3706 3416 3417 3562 3423 3571 3707 3566 3276 3416 3572 3422 3705 3567 3278 3566 3572 3708 3573 3568 3419 3567 3573 3709 3710 3569 3420 3568 3427 3574 3710 3569 3570 3421 3428 3711 3575 3570 3707 3571 3575 3712 3713 3707 3422 3423 3431 3576 3713 3422 3572 3284 3432 3714 3715 3572 3573 3425 3580 3430 3715 3573 3710 3574 3580 3578 3435 3710 3428 3427 3584 3435 3577 3428 3575 3426 3584 3582 3585 3576 3575 3713 3438 3585 3581 3431 3713 3432 3439 3716 3717 3430 3432 3715 3442 3437 3717 3580 3715 3578 3589 3442 3718 3435 3578 3577 3589 3587 3590 3584 3577 3582 3591 3590 3586 3581 3585 3582 3301 3591 3719 3439 3438 3581 3595 3301 3720 3717 3437 3439 3595 3593 3596 3718 3442 3717 3596 3592 3597 3587 3589 3718 3597 3721 3598 3587 3586 3590 3599 3598 3722 3586 3719 3591 3600 3599 3723 3719 3720 3301 3601 3600 3724 3720 3593 3595 3602 3601 3725 3593 3592 3596 3603 3602 3726 3592 3721 3597 3604 3603 3727 3598 3721 3722 3605 3604 3728 3599 3722 3723 3606 3605 3729 3600 3723 3724 3607 3606 3730 3601 3724 3725 3608 3607 3731 3602 3725 3726 3609 3608 3732 3603 3726 3727 3460 3609 3733 3604 3727 3728 3734 3735 3736 3728 3729 3605 3459 3737 3610 3729 3730 3606 3611 3610 3738 3730 3731 3607 3321 3611 3739 3731 3732 3608 3740 3741 3742 3733 3609 3732 3613 3743 3614 3461 3460 3733 3326 3614 3744 3737 3459 3461 3745 3746 3747 3738 3610 3737 3467 3616 3748 3739 3611 3738 3620 3467 3749 3321 3739 3612 3620 3618 3469 3613 3612 3743 3750 3751 3752 3614 3743 3744 3471 3621 3753 3326 3744 3615 3622 3751 3754 3616 3615 3748 3473 3623 3754 3467 3748 3749 3474 3755 3624 3749 3618 3620 3756 3757 3758 3618 3617 3469 3477 3625 3759 3621 3617 3753 3478 3757 3626 3753 3622 3471 3626 3760 3627 3622 3754 3623 3627 3761 3762 3474 3473 3754 3630 3481 3762 3624 3472 3474 3482 3630 3629 3624 3759 3625 3483 3763 3631 3478 3477 3759 3631 3764 3632 3626 3476 3478 3632 3765 3633 3627 3480 3626 3633 3766 3634 3762 3481 3627 3634 3767 3635 3629 3630 3762 3768 3769 3770 3482 3629 3483 3771 3637 3769 3342 3483 3631 3639 3490 3772 3485 3631 3632 3493 3639 3638 3633 3486 3632 3494 3491 3773 3634 3487 3633 3494 3774 3640 3635 3488 3634 3640 3775 3641 3636 3489 3635 3641 3776 3642 3772 3490 3636 3642 3777 3643 3638 3639 3772 3778 3644 3779 3491 3493 3638 3646 3499 3780 3492 3491 3494 3501 3646 3645 3640 3352 3494 3502 3781 3647 3641 3496 3640 3647 3782 3648 3642 3497 3641 3783 3784 3785 3643 3498 3642 3362 3649 3786 3643 3780 3499 3650 3784 3651 3780 3645 3646 3787 3788 3789 3502 3501 3645 3507 3510 3654 3502 3647 3500 3652 3788 3790 3647 3648 3504 128 3653 3790 3649 3648 3786 3791 124 3508 3650 3362 3786 125 133 3655 3650 3651 3506 3652 3789 3788 3651 3654 3510 3792 113 115 3656 131 3793 3655 3511 125 3653 3652 3790 3657 3793 3794 128 3790 3508 3795 3658 3794 124 126 3508 3796 3659 3795 133 125 124 3797 3793 131 130 129 3655 3798 3799 3800 3662 3660 3512 3659 3374 3517 3793 3657 3656 3801 3661 3660 3657 3794 3658 3661 3799 3663 3658 3795 3659 3802 3662 3803 3514 3513 3796 3664 3519 3798 3520 3664 3804 3661 3663 3522 3801 3660 3662 3665 3523 3804 3801 3799 3661 3804 3664 3805 3663 3798 3519 3524 3666 3668 3666 3806 3807 3379 3523 3380 3523 3520 3804 3103 3667 3808 2811 2810 3667 3526 3524 3668 3667 3668 3809 3103 2811 3667 3101 3530 3102 3810 3238 3240 3810 3532 3238 3530 3669 3105 3238 3811 3669 3812 3813 3814 3811 3386 3670 3815 3816 3817 3385 3670 3386 3817 3818 3819 3385 3387 3535 3390 3537 3672 3535 3534 3538 3393 3390 3671 3536 3538 3534 3391 3674 3541 3672 3537 3536 3820 3821 3822 3671 3390 3672 3823 3820 3824 3393 3671 3674 3676 3677 3397 3393 3674 3391 679 552 3543 3541 3540 3391 672 3825 3826 3396 3540 3539 560 673 3826 3397 3396 3676 3680 3827 3828 3397 3677 3543 3546 3681 3828 3543 3677 679 3682 3544 3829 552 679 678 3682 3830 3831 678 672 674 3550 3683 3831 673 672 3826 3684 3548 3832 3826 3680 560 3684 3833 3685 3680 3828 3681 3834 3686 3835 3828 3544 3546 3689 3553 3836 3682 3545 3544 3406 3689 3688 3682 3831 3683 3690 3687 3837 3831 3548 3550 3690 3838 3691 3684 3549 3548 3691 3839 3692 3685 3552 3684 3692 3840 3693 3836 3553 3685 3841 3694 3842 3688 3689 3836 3560 3559 3843 3687 3406 3688 3698 3560 3696 3555 3687 3690 3563 3698 3695 3691 3556 3690 3564 3561 3844 3692 3557 3691 3699 3564 3845 3693 3558 3692 3700 3699 3846 3843 3559 3693 3700 3847 3701 3696 3560 3843 3701 3848 3702 3695 3698 3696 3702 3849 3703 3561 3563 3695 3850 3704 3851 3564 3562 3561 3707 3570 3852 3699 3416 3564 3422 3707 3706 3700 3566 3699 3708 3705 3853 3701 3567 3700 3708 3854 3709 3702 3568 3701 3855 3856 3857 3703 3569 3702 3428 3710 3858 3703 3852 3570 3711 3856 3712 3852 3706 3707 3859 3860 3861 3706 3705 3422 3432 3713 3862 3705 3708 3572 3714 3860 3863 3708 3709 3573 3578 3715 3863 3710 3709 3858 3579 3864 3865 3858 3711 3428 3582 3577 3865 3575 3711 3712 3583 3866 3867 3713 3712 3862 3439 3581 3867 3432 3862 3714 3716 3868 3869 3715 3714 3863 3718 3717 3869 3578 3863 3579 3587 3718 3870 3865 3577 3579 3588 3871 3872 3582 3865 3583 3719 3586 3872 3867 3581 3583 3720 3719 3873 3716 3439 3867 3593 3720 3874 3716 3869 3717 3875 3876 3877 3870 3718 3869 3592 3878 3721 3588 3587 3870 3721 3879 3722 3588 3872 3586 3723 3722 3880 3872 3873 3719 3724 3723 3881 3873 3874 3720 3725 3724 3882 3874 3594 3593 3726 3725 3883 3594 3878 3592 3727 3726 3884 3721 3878 3879 3728 3727 3885 3722 3879 3880 3729 3728 3886 3723 3880 3881 3730 3729 3887 3724 3881 3882 3731 3730 3888 3725 3882 3883 3732 3731 3889 3726 3883 3884 3733 3732 3890 3727 3884 3885 3461 3733 3891 3728 3885 3886 3737 3461 3892 3886 3887 3729 3737 3735 3738 3887 3888 3730 3739 3738 3734 3888 3889 3731 3612 3739 3893 3889 3890 3732 3743 3612 3894 3891 3733 3890 3743 3741 3744 3892 3461 3891 3615 3744 3740 3735 3737 3892 3748 3615 3895 3734 3738 3735 3749 3748 3747 3893 3739 3734 3618 3749 3746 3894 3612 3893 3619 3896 3897 3743 3894 3741 3753 3617 3897 3744 3741 3740 3622 3753 3752 3615 3740 3895 3898 3899 3900 3748 3895 3747 3474 3754 3901 3749 3747 3746 3755 3899 3902 3746 3619 3618 3759 3624 3902 3619 3897 3617 3478 3759 3758 3753 3897 3752 3757 3903 3760 3752 3751 3622 3760 3904 3761 3751 3901 3754 3905 3906 3907 3755 3474 3901 3629 3762 3908 3755 3902 3624 3763 3628 3906 3902 3758 3759 3764 3763 3909 3757 3478 3758 3764 3910 3765 3760 3626 3757 3765 3911 3766 3761 3627 3760 3766 3912 3767 3908 3762 3761 3913 3768 3914 3628 3629 3908 3636 3635 3915 3763 3483 3628 3772 3636 3770 3631 3763 3764 3638 3772 3769 3765 3632 3764 3773 3637 3916 3766 3633 3765 3774 3773 3917 3767 3634 3766 3775 3774 3918 3915 3635 3767 3775 3919 3776 3770 3636 3915 3776 3920 3777 3769 3772 3770 3921 3778 3922 3637 3638 3769 3780 3643 3923 3773 3491 3637 3645 3780 3779 3773 3774 3494 3781 3644 3924 3775 3640 3774 3781 3925 3782 3776 3641 3775 3782 3926 3927 3777 3642 3776 3786 3648 3927 3923 3643 3777 3650 3786 3785 3923 3779 3780 3784 3928 3929 3779 3644 3645 3654 3651 3929 3781 3502 3644 3652 3654 3789 3781 3782 3647 3930 3931 3932 3782 3927 3648 3508 3790 3933 3786 3927 3785 3791 3931 132 3784 3650 3785 133 135 130 3929 3651 3784 3788 3787 3934 3929 3789 3654 3797 131 137 3935 3793 3797 130 3655 133 3790 3788 3933 3936 3794 3935 3933 3791 3508 3795 3936 3937 124 3791 132 3938 3796 3937 135 133 132 3935 3797 3792 137 131 130 3514 3803 3662 3662 3802 3801 3796 3513 3659 3793 3935 3794 3801 3939 3799 3936 3795 3794 3940 3941 3802 3795 3937 3796 3664 3942 3805 3514 3938 3803 3804 3805 3943 3943 3806 3665 3799 3798 3663 3939 3801 3802 3805 3944 3943 3800 3799 3939 3807 3809 3666 3798 3942 3664 3945 3946 3807 3947 3808 3948 3523 3665 3524 3804 3943 3665 3239 3808 3947 3667 3809 3808 3668 3666 3809 3809 3948 3808 3103 3808 3239 3101 3238 3669 3531 3532 3810 3949 3950 3951 3669 3811 3670 3532 3952 3811 3953 3954 3387 3953 3386 3952 3954 3955 3534 3386 3953 3387 3672 3536 3956 3534 3387 3954 3957 3958 3959 3534 3955 3536 3960 3958 3961 3956 3536 3955 3541 3962 3821 3673 3672 3956 3821 3823 3539 3671 3673 3675 3823 3678 3676 3962 3674 3675 3963 3964 3965 3674 3962 3541 3966 546 683 3539 3541 3821 3967 3968 3969 3676 3539 3823 3680 3826 3970 3677 3676 3678 3827 3968 3971 679 3677 3679 3544 3828 3971 679 3679 677 3830 3829 3972 678 677 680 3973 3974 3975 680 3825 672 3548 3831 3976 3826 3825 3970 3833 3832 3974 3970 3827 3680 3833 3977 3978 3827 3971 3828 3836 3685 3978 3971 3829 3544 3688 3836 3835 3829 3830 3682 3837 3686 3979 3830 3976 3831 3838 3837 3980 3976 3832 3548 3838 3981 3839 3833 3684 3832 3839 3982 3840 3978 3685 3833 3983 3841 3984 3835 3836 3978 3843 3693 3985 3686 3688 3835 3696 3843 3842 3686 3837 3687 3697 3694 3986 3838 3690 3837 3844 3697 3987 3839 3691 3838 3845 3844 3988 3840 3692 3839 3846 3845 3989 3985 3693 3840 3847 3846 3990 3842 3843 3985 3847 3991 3848 3694 3696 3842 3848 3992 3849 3697 3695 3694 3993 3850 3994 3844 3561 3697 3852 3703 3995 3845 3564 3844 3706 3852 3851 3845 3846 3699 3853 3704 3996 3847 3700 3846 3854 3853 3997 3848 3701 3847 3854 3998 3999 3849 3702 3848 3858 3709 3999 3995 3703 3849 3711 3858 3857 3995 3851 3852 3856 4000 4001 3851 3704 3706 3862 3712 4001 3704 3853 3705 3714 3862 3861 3853 3854 3708 3860 4002 4003 3854 3999 3709 3579 3863 4003 3858 3999 3857 4004 3864 4005 3857 3856 3711 3583 3865 4004 3712 3856 4001 3866 4006 4007 3862 4001 3861 3716 3867 4007 3714 3861 3860 4008 4009 4010 3863 3860 4003 3870 3869 4011 3864 3579 4003 3588 3870 4012 4004 3865 3864 4013 4014 4015 3583 4004 3866 3873 3872 4016 4007 3867 3866 3874 3873 4017 3868 3716 4007 3594 3874 4018 3868 4011 3869 3878 3594 4019 4012 3870 4011 3878 3876 3879 3871 3588 4012 3880 3879 3875 3871 4016 3872 3881 3880 4020 4016 4017 3873 3882 3881 4021 4017 4018 3874 3883 3882 4022 4018 4019 3594 3884 3883 4023 4019 3876 3878 3885 3884 4024 3879 3876 3875 3886 3885 4025 3880 3875 4020 3887 3886 4026 3881 4020 4021 3888 3887 4027 3882 4021 4022 3889 3888 4028 3883 4022 4023 3890 3889 4029 3884 4023 4024 3891 3890 4030 3885 4024 4025 3892 3891 4031 3886 4025 4026 3735 3892 4032 3887 4026 4027 4033 4034 4035 4027 4028 3888 3893 3734 4036 4028 4029 3889 3894 3893 4037 4029 4030 3890 3741 3894 4038 4030 4031 3891 3742 4039 4040 4032 3892 4031 3895 3740 4040 3736 3735 4032 3747 3895 4041 3736 4036 3734 4042 3745 4043 4037 3893 4036 3619 3746 4042 4038 3894 4037 3896 4044 4045 3741 4038 3742 3752 3897 4045 4040 3740 3742 4046 3750 4047 3895 4040 4041 3901 3751 4046 3747 4041 3745 3755 3901 3900 3746 3745 4042 3899 4048 4049 4042 3896 3619 3758 3902 4049 3897 3896 4045 3903 3756 4050 3752 4045 3750 3904 3903 4051 3750 4046 3751 4052 3905 4053 4046 3900 3901 3908 3761 4054 3899 3755 3900 3628 3908 3907 3899 4049 3902 3909 3906 4055 4049 3756 3758 3910 3909 4056 3756 3903 3757 3910 4057 3911 3904 3760 3903 4058 4059 4060 4054 3761 3904 4061 3913 4059 3907 3908 4054 3915 3767 4062 3906 3628 3907 3770 3915 3914 3906 3909 3763 3771 3768 4063 3910 3764 3909 3916 3771 4064 3911 3765 3910 3917 3916 4065 3912 3766 3911 3918 3917 4066 4062 3767 3912 3919 3918 4067 3914 3915 4062 3919 4068 3920 3768 3770 3914 4069 3921 4070 3771 3769 3768 3923 3777 4071 3916 3637 3771 3779 3923 3922 3916 3917 3773 3924 3778 4072 3917 3918 3774 3925 3924 4073 3919 3775 3918 3925 4074 3926 3920 3776 3919 4075 4076 4077 4071 3777 3920 3785 3927 4078 4071 3922 3923 3928 3783 4076 3922 3778 3779 3928 4079 4080 3778 3924 3644 3789 3929 4080 3924 3925 3781 3934 3787 4081 3925 3926 3782 3933 3788 3934 3926 4078 3927 3791 3933 3932 3785 4078 3783 4082 148 4083 3783 3928 3784 150 4084 155 3928 4080 3929 3934 4081 4085 4080 3787 3789 3792 3797 149 3935 3792 115 137 130 135 3934 3932 3933 4086 3936 115 3932 3931 3791 4087 3937 4086 132 3931 138 4088 3938 4087 135 138 136 4089 4090 4091 149 3797 137 3803 3940 3802 3941 3939 3802 3938 3514 3796 3935 115 3936 3939 4090 3800 3936 4086 3937 3800 4089 3942 3937 4087 3938 4092 3941 4093 3940 3803 4088 3944 3805 4094 4095 3943 3944 3800 3942 3798 3941 4090 3939 3945 3806 4095 4090 4089 3800 4095 3944 4096 3942 4094 3805 3807 3946 3948 3946 4097 4098 3665 3806 3666 3806 3943 4095 3947 4099 4100 3240 3239 3947 3809 3807 3948 3947 3948 4099 3810 3240 3947 3238 3532 3811 3528 3527 3531 3529 3813 3527 3811 3952 3386 3527 4101 3952 3954 4102 3815 4102 3953 4101 3815 3819 3955 3954 3953 4102 3959 3673 3956 3954 3815 3955 3675 3673 3958 3819 3956 3955 3962 3675 3960 3819 3959 3956 4103 4104 4105 3958 3673 3959 4106 4107 4108 3960 3675 3958 3824 3963 3678 3962 3960 3822 3963 4109 3679 3822 3821 3962 3825 680 547 3820 3823 3821 3970 3825 554 3823 3824 3678 3827 3970 3969 3679 3678 3963 4110 4111 4112 3679 4109 677 3829 3971 4113 677 4109 545 4114 3972 4115 680 545 547 3976 3830 4114 547 554 3825 3832 3976 3975 3970 554 3969 3977 3974 4116 3969 3968 3827 4117 4118 4119 3968 4113 3971 3835 3978 4120 3829 4113 3972 3979 3834 4121 3972 4114 3830 3980 3979 4122 4114 3975 3976 3981 3980 4123 3975 3974 3832 3981 4124 3982 3977 3833 3974 4125 4126 4127 4120 3978 3977 3985 3840 4128 3834 3835 4120 3842 3985 3984 3834 3979 3686 3986 3841 4129 3979 3980 3837 3987 3986 4130 3981 3838 3980 3988 3987 4131 3982 3839 3981 3989 3988 4132 4128 3840 3982 3990 3989 4133 3984 3985 4128 3991 3990 4134 3841 3842 3984 3991 4135 3992 3986 3694 3841 4136 4137 4138 3987 3697 3986 3995 3849 4139 3988 3844 3987 3851 3995 3994 3988 3989 3845 3996 3850 4140 3989 3990 3846 3997 3996 4141 3991 3847 3990 3998 3997 4142 3992 3848 3991 4143 4144 4145 4139 3849 3992 3857 3999 4146 4139 3994 3995 4000 3855 4147 3994 3850 3851 4148 4000 4149 3850 3996 3704 3861 4001 4148 3853 3996 3997 4002 3859 4150 3997 3998 3854 4151 4152 4153 3998 4146 3999 3864 4003 4154 3857 4146 3855 4155 4005 4156 3856 3855 4000 3866 4004 4155 4001 4000 4148 4006 4157 4158 3861 4148 3859 3868 4007 4158 3860 3859 4002 4011 3868 4159 4003 4002 4154 4012 4011 4010 4005 3864 4154 3871 4012 4009 4155 4004 4005 4016 3871 4160 3866 4155 4006 4017 4016 4015 4158 4007 4006 4018 4017 4014 4159 3868 4158 4019 4018 4161 4159 4010 4011 3876 4019 4162 4010 4009 4012 4163 4164 4165 4160 3871 4009 4020 3875 4166 4160 4015 4016 4021 4020 4167 4015 4014 4017 4022 4021 4168 4014 4161 4018 4023 4022 4169 4161 4162 4019 4024 4023 4170 4162 3877 3876 4025 4024 4171 3875 3877 4166 4026 4025 4172 4020 4166 4167 4027 4026 4173 4021 4167 4168 4028 4027 4174 4022 4168 4169 4029 4028 4175 4023 4169 4170 4030 4029 4176 4024 4170 4171 4031 4030 4177 4025 4171 4172 4032 4031 4178 4026 4172 4173 3736 4032 4179 4027 4173 4174 4036 3736 4180 4174 4175 4028 4037 4036 4035 4175 4176 4029 4038 4037 4034 4176 4177 4030 3742 4038 4181 4177 4178 4031 4182 4183 4184 4179 4032 4178 4041 4040 4185 4180 3736 4179 3745 4041 4186 4180 4035 4036 4187 4043 4188 4034 4037 4035 3896 4042 4187 4181 4038 4034 4189 4044 4190 3742 4181 4039 3750 4045 4189 4185 4040 4039 4191 4047 4192 4041 4185 4186 3900 4046 4191 4043 3745 4186 4048 3898 4193 4042 4043 4187 4194 4195 4196 3896 4187 4044 3756 4049 4197 4045 4044 4189 4051 4050 4198 3750 4189 4047 4199 4051 4200 4047 4191 4046 4054 3904 4199 4191 3898 3900 3907 4054 4053 3898 4048 3899 4055 3905 4201 4048 4197 4049 4056 4055 4202 4197 4050 3756 4057 4056 4203 4050 4051 3903 4204 4205 4206 4199 3904 4051 3912 3911 4207 4053 4054 4199 4062 3912 4060 3905 3907 4053 3914 4062 4059 3905 4055 3906 4063 3913 4208 4055 4056 3909 4064 4063 4209 4057 3910 4056 4065 4064 4210 4207 3911 4057 4066 4065 4211 4060 3912 4207 4067 4066 4212 4059 4062 4060 4068 4067 4213 3913 3914 4059 4214 4215 4216 4063 3768 3913 4071 3920 4217 4064 3771 4063 3922 4071 4070 4064 4065 3916 4072 3921 4218 4065 4066 3917 4073 4072 4219 4066 4067 3918 4074 4073 4220 4068 3919 4067 4221 4222 4223 4217 3920 4068 4078 3926 4224 4070 4071 4217 3783 4078 4077 4070 3921 3922 4079 4076 4225 3921 4072 3778 4226 4227 4228 4072 4073 3924 3787 4080 4229 4073 4074 3925 4085 4081 4230 4074 4224 3926 3932 3934 4085 4078 4224 4077 4231 3930 141 3783 4077 4076 138 3931 4231 4076 4079 3928 136 138 4083 4079 4229 4080 4085 4230 139 3787 4229 4081 113 3792 4232 4233 4234 4235 149 137 136 4085 3930 3932 4086 114 4236 3930 4231 3931 4237 4087 4236 138 4231 4083 4238 4088 4237 148 136 4083 114 113 4084 4232 3792 149 3940 4093 3941 3941 4092 4090 4088 3803 3938 114 4086 115 4239 4240 4096 4086 4236 4087 4089 4241 4094 4087 4237 4088 4092 4234 4233 3940 4238 4093 4096 3944 4242 4095 4096 4243 4089 4094 3942 4091 4090 4092 4097 3945 4243 4091 4241 4089 4243 4096 4240 4094 4242 3944 3946 4098 4099 4244 4245 4100 3806 3945 3807 3945 4095 4243 3531 4100 4245 4100 3810 3947 3948 3946 4099 4100 4099 4244 3531 3810 4100 3527 3952 3532 3814 3813 3529 4246 4247 4248 3952 4101 3953 3813 4249 4101 4250 4251 4252 4249 3816 4102 4253 4254 4255 3815 4102 3816 4256 4257 4253 3815 3817 3819 4258 4259 4260 3819 3818 3959 3822 3960 4104 3957 3959 3818 3820 4103 4107 3961 3958 3957 4107 3964 3824 4104 3960 3961 4261 4262 4263 3822 4104 4103 3965 686 4109 3822 4103 3820 3966 4264 555 3824 3820 4107 3969 554 4265 3964 3963 3824 4266 4267 3967 4109 3963 3965 4113 3968 4268 4109 686 545 3972 4113 4110 545 686 546 4269 4270 4271 547 546 555 3975 4114 4272 554 555 4265 4270 4273 3973 3969 4265 3967 4273 4274 4116 3967 4268 3968 4120 3977 4275 4268 4110 4113 3834 4120 4117 3972 4110 4115 4119 4276 4121 4115 4272 4114 4276 4277 4122 4272 3973 3975 4278 4279 4280 3973 4116 3974 4281 4126 4278 4275 3977 4116 4128 3982 4282 4117 4120 4275 3984 4128 4125 4117 4121 3834 4127 4283 3983 4121 4122 3979 4283 4284 4129 4122 4123 3980 4284 4285 4130 4123 4124 3981 4285 4286 4131 4282 3982 4124 4286 4287 4132 4125 4128 4282 4287 4288 4133 3983 3984 4125 4289 4290 4291 4129 3841 3983 4292 4137 4289 4130 3986 4129 4139 3992 4293 4131 3987 4130 3994 4139 4136 4131 4132 3988 4138 4294 3993 4132 4133 3989 4294 4295 4140 4133 4134 3990 4295 4296 4141 4134 4135 3991 4297 4144 4298 4293 3992 4135 4146 3998 4299 4136 4139 4293 3855 4146 4143 4136 3993 3994 4145 4300 4147 3993 4140 3850 4301 4302 4303 4140 4141 3996 3859 4148 4304 3997 4141 4142 4302 4305 4150 4142 4299 3998 4154 4002 4306 4299 4143 4146 4005 4154 4151 3855 4143 4147 4307 4308 4309 4000 4147 4149 4006 4155 4310 4148 4149 4304 4311 4312 4313 3859 4304 4150 4159 4158 4314 4002 4150 4306 4010 4159 4315 4151 4154 4306 4316 4317 4008 4156 4005 4151 4160 4009 4318 4310 4155 4156 4015 4160 4319 4310 4157 4006 4320 4321 4013 4314 4158 4157 4161 4014 4322 4315 4159 4314 4162 4161 4323 4315 4008 4010 3877 4162 4324 4008 4318 4009 4166 3877 4325 4319 4160 4318 4167 4166 4326 4319 4013 4015 4168 4167 4327 4013 4322 4014 4169 4168 4328 4322 4323 4161 4170 4169 4329 4323 4324 4162 4171 4170 4330 4324 4325 3877 4172 4171 4331 4166 4325 4326 4173 4172 4332 4167 4326 4327 4174 4173 4333 4168 4327 4328 4175 4174 4334 4169 4328 4329 4176 4175 4335 4170 4329 4330 4177 4176 4336 4171 4330 4331 4178 4177 4337 4172 4331 4332 4179 4178 4338 4173 4332 4333 4180 4179 4339 4174 4333 4334 4035 4180 4340 4175 4334 4335 4341 4342 4343 4335 4336 4176 4181 4034 4344 4336 4337 4177 4039 4181 4345 4337 4338 4178 4185 4039 4346 4339 4179 4338 4186 4185 4182 4340 4180 4339 4043 4186 4347 4340 4033 4035 4348 4349 4350 4344 4034 4033 4044 4187 4351 4345 4181 4344 4352 4353 4354 4039 4345 4346 4047 4189 4355 4182 4185 4346 4356 4357 4358 4186 4182 4347 3898 4191 4359 4188 4043 4347 4357 4360 4193 4187 4188 4351 4197 4048 4361 4044 4351 4190 4050 4197 4194 4189 4190 4355 4196 4362 4198 4047 4355 4192 4363 4364 4365 4192 4359 4191 4053 4199 4366 3898 4359 4193 4364 4367 4052 4193 4361 4048 4367 4368 4201 4361 4194 4197 4368 4369 4202 4194 4198 4050 4370 4205 4371 4198 4200 4051 4207 4057 4372 4366 4199 4200 4060 4207 4204 4366 4052 4053 4206 4373 4058 4052 4201 3905 4373 4374 4061 4201 4202 4055 4374 4375 4208 4202 4203 4056 4375 4376 4209 4372 4057 4203 4376 4377 4210 4204 4207 4372 4377 4378 4211 4058 4060 4204 4378 4379 4212 4061 4059 4058 4380 4215 4381 4208 3913 4061 4217 4068 4382 4209 4063 4208 4070 4217 4214 4209 4210 4064 4216 4383 4069 4210 4211 4065 4383 4384 4218 4211 4212 4066 4384 4385 4219 4212 4213 4067 4385 4386 4220 4382 4068 4213 4224 4074 4387 4214 4217 4382 4077 4224 4221 4214 4069 4070 4223 4388 4075 4069 4218 3921 4388 4389 4225 4218 4219 4072 4229 4079 4390 4219 4220 4073 4081 4229 4226 4220 4387 4074 4228 4391 4230 4387 4221 4224 3930 4085 139 4077 4221 4075 140 4392 141 4076 4075 4225 4083 4231 4393 4079 4225 4390 4394 4395 4082 4229 4390 4226 4232 148 4396 4081 4226 4230 4084 113 156 114 4084 4397 4232 149 148 3930 139 141 4398 4236 4397 4231 141 4393 4399 4237 4398 4083 4393 4082 4400 4238 4399 148 4082 4396 4397 4084 150 156 113 4232 4093 4234 4092 4233 4091 4092 4238 3940 4088 114 4397 4236 4091 4401 4241 4236 4398 4237 4241 4402 4242 4238 4237 4399 4403 4233 4235 4093 4400 4234 4243 4240 4404 4404 4405 4097 4241 4242 4094 4401 4091 4233 4240 4406 4404 4402 4241 4401 4407 4244 4098 4242 4239 4096 4408 4409 4407 4410 4245 4411 3945 4097 3946 4243 4404 4097 4407 4098 4405 4245 3529 3528 4099 4098 4244 4244 4411 4245 3531 4245 3528 3527 3813 4101 3951 3812 3814 3950 3812 3951 4101 4249 4102 3812 4412 4249 4413 4254 3817 4413 3816 4412 4254 4257 3818 3816 4413 3817 4260 3961 3957 3817 4254 3818 4104 3961 4259 3818 4257 3957 4414 4415 4416 4257 4260 3957 4417 4414 4418 4259 3961 4260 3964 4106 4262 4104 4259 4105 4262 687 3965 4108 4103 4105 684 4419 549 4108 4107 4103 4420 4421 4264 4106 3964 4107 4264 4266 4265 4262 3965 3964 4422 4423 4267 3965 687 686 4267 4111 4268 683 546 686 4424 4425 4112 555 546 3966 4112 4426 4115 4265 555 4264 4426 4270 4272 3967 4265 4266 4269 4427 4273 4268 3967 4267 4428 4429 4430 4268 4111 4110 4274 4118 4275 4115 4110 4112 4429 4431 4119 4272 4115 4426 4431 4432 4276 4272 4270 3973 4433 4280 4434 3973 4273 4116 4277 4435 4123 4116 4274 4275 4435 4279 4124 4118 4117 4275 4279 4126 4282 4117 4119 4121 4281 4436 4127 4121 4276 4122 4436 4437 4283 4122 4277 4123 4437 4438 4284 4123 4435 4124 4438 4439 4285 4124 4279 4282 4439 4440 4286 4126 4125 4282 4441 4442 4443 4127 3983 4125 4444 4291 4441 4283 4129 3983 4288 4445 4134 4284 4130 4129 4445 4290 4135 4285 4131 4130 4290 4137 4293 4131 4286 4132 4292 4446 4138 4132 4287 4133 4446 4447 4294 4133 4288 4134 4447 4448 4295 4134 4445 4135 4449 4298 4450 4135 4290 4293 4296 4451 4142 4137 4136 4293 4451 4144 4299 4136 4138 3993 4297 4452 4145 3993 4294 4140 4452 4453 4300 4140 4295 4141 4300 4454 4149 4141 4296 4142 4454 4302 4304 4299 4142 4451 4301 4455 4305 4299 4144 4143 4305 4152 4306 4147 4143 4145 4456 4457 4153 4149 4147 4300 4153 4458 4156 4304 4149 4454 4458 4308 4310 4150 4304 4302 4308 4459 4157 4306 4150 4305 4459 4312 4314 4151 4306 4152 4312 4316 4315 4153 4156 4151 4460 4461 4462 4458 4310 4156 4317 4463 4318 4308 4157 4310 4463 4320 4319 4157 4459 4314 4464 4465 4466 4312 4315 4314 4321 4467 4322 4316 4008 4315 4467 4468 4323 4008 4317 4318 4468 4469 4324 4318 4463 4319 4469 4470 4325 4319 4320 4013 4470 4471 4326 4013 4321 4322 4471 4472 4327 4322 4467 4323 4472 4473 4328 4323 4468 4324 4473 4474 4329 4324 4469 4325 4474 4475 4330 4325 4470 4326 4475 4476 4331 4327 4326 4471 4476 4477 4332 4328 4327 4472 4477 4478 4333 4329 4328 4473 4478 4479 4334 4330 4329 4474 4479 4480 4335 4331 4330 4475 4480 4481 4336 4332 4331 4476 4481 4482 4337 4333 4332 4477 4482 4483 4338 4334 4333 4478 4483 4484 4339 4335 4334 4479 4484 4485 4340 4336 4335 4480 4485 4486 4033 4336 4481 4337 4486 4342 4344 4337 4482 4338 4342 4487 4345 4338 4483 4339 4487 4183 4346 4339 4484 4340 4488 4489 4184 4485 4033 4340 4184 4490 4347 4033 4486 4344 4490 4491 4188 4342 4345 4344 4491 4349 4351 4487 4346 4345 4349 4492 4190 4182 4346 4183 4492 4353 4355 4184 4347 4182 4353 4493 4192 4188 4347 4490 4493 4357 4359 4491 4351 4188 4356 4494 4360 4190 4351 4349 4360 4195 4361 4492 4355 4190 4495 4496 4196 4192 4355 4353 4496 4497 4362 4359 4192 4493 4362 4498 4200 4359 4357 4193 4498 4364 4366 4361 4193 4360 4363 4499 4367 4361 4195 4194 4499 4500 4368 4194 4196 4198 4501 4371 4502 4198 4362 4200 4369 4503 4203 4200 4498 4366 4503 4205 4372 4366 4364 4052 4370 4504 4206 4052 4367 4201 4504 4505 4373 4201 4368 4202 4505 4506 4374 4202 4369 4203 4506 4507 4375 4203 4503 4372 4507 4508 4376 4205 4204 4372 4508 4509 4377 4206 4058 4204 4510 4511 4512 4373 4061 4058 4513 4381 4510 4374 4208 4061 4379 4514 4213 4375 4209 4208 4514 4215 4382 4209 4376 4210 4380 4515 4216 4210 4377 4211 4515 4516 4383 4211 4378 4212 4516 4517 4384 4212 4379 4213 4517 4518 4385 4213 4514 4382 4519 4520 4521 4215 4214 4382 4386 4222 4387 4214 4216 4069 4520 4522 4223 4069 4383 4218 4522 4523 4388 4218 4384 4219 4524 4525 4526 4219 4385 4220 4389 4227 4390 4387 4220 4386 4525 4527 4228 4221 4387 4222 4528 4529 4530 4221 4223 4075 4391 140 139 4225 4075 4388 4529 4531 4392 4390 4225 4389 4392 4394 4393 4226 4390 4227 4532 4533 4395 4230 4226 4228 4395 157 4396 4391 139 4230 4534 4535 153 4397 150 144 156 4232 4396 4393 141 4392 4398 144 4536 4082 4393 4394 4537 4399 4536 4396 4082 4395 4538 4400 4537 156 4396 157 142 144 150 155 4084 156 4539 4540 4541 4403 4401 4233 4400 4093 4238 144 4398 4397 4542 4402 4401 4398 4536 4399 4402 4540 4239 4399 4537 4400 4543 4403 4544 4235 4234 4538 4406 4240 4539 4545 4404 4406 4402 4239 4242 4542 4401 4403 4408 4405 4545 4542 4540 4402 4545 4406 4546 4239 4539 4240 4407 4409 4411 4409 4547 4548 4097 4405 4098 4405 4404 4545 3814 4410 4549 4410 3529 4245 4244 4407 4411 4410 4411 4550 3814 3529 4410 3812 4249 3813 4551 3950 3949 4551 4251 3950 4249 4412 3816 3950 4552 4412 4553 4247 4554 4255 4413 4552 4555 4556 4557 4254 4413 4255 4557 4558 4559 4254 4253 4257 4105 4259 4415 4257 4256 4260 4108 4105 4414 4258 4260 4256 4106 4417 4263 4415 4259 4258 4560 4561 4562 4414 4105 4415 4261 684 687 4414 4417 4108 4420 3966 681 4108 4417 4106 4563 4564 4565 4263 4262 4106 4422 4266 4421 687 4262 4261 4566 4567 4568 687 684 683 4424 4111 4423 681 3966 683 4569 4425 4566 4264 3966 4420 4271 4426 4425 4421 4266 4264 4570 4571 4269 4267 4266 4422 4572 4427 4571 4111 4267 4423 4573 4274 4427 4111 4424 4112 4429 4118 4573 4426 4112 4425 4574 4431 4428 4270 4426 4271 4575 4432 4574 4270 4269 4273 4576 4277 4432 4273 4427 4274 4280 4435 4576 4118 4274 4573 4433 4577 4278 4118 4429 4119 4577 4578 4281 4119 4431 4276 4579 4436 4578 4276 4432 4277 4580 4437 4579 4277 4576 4435 4581 4438 4580 4435 4280 4279 4582 4583 4584 4279 4278 4126 4443 4584 4585 4281 4127 4126 4586 4287 4440 4436 4283 4127 4442 4288 4586 4437 4284 4283 4291 4445 4442 4284 4438 4285 4444 4587 4289 4285 4439 4286 4587 4588 4292 4286 4440 4287 4589 4446 4588 4287 4586 4288 4590 4447 4589 4288 4442 4445 4450 4591 4592 4445 4291 4290 4593 4296 4448 4290 4289 4137 4298 4451 4593 4137 4292 4138 4449 4594 4297 4138 4446 4294 4595 4452 4594 4294 4447 4295 4596 4597 4598 4295 4448 4296 4303 4454 4453 4451 4296 4593 4596 4599 4301 4144 4451 4298 4600 4601 4602 4144 4297 4145 4456 4152 4455 4300 4145 4452 4603 4457 4600 4454 4300 4453 4309 4458 4457 4303 4302 4454 4604 4605 4307 4305 4302 4301 4313 4459 4307 4455 4152 4305 4606 4607 4311 4153 4152 4456 4608 4316 4311 4457 4458 4153 4609 4317 4608 4309 4308 4458 4461 4463 4609 4307 4459 4308 4610 4320 4461 4459 4313 4312 4611 4321 4610 4311 4316 4312 4465 4467 4611 4608 4317 4316 4612 4468 4465 4317 4609 4463 4613 4469 4612 4463 4461 4320 4614 4470 4613 4320 4610 4321 4615 4471 4614 4467 4321 4611 4615 4616 4472 4467 4465 4468 4617 4473 4616 4468 4612 4469 4163 4474 4617 4469 4613 4470 4618 4475 4163 4470 4614 4471 4619 4476 4618 4472 4471 4615 4620 4477 4619 4473 4472 4616 4479 4621 4622 4474 4473 4617 4623 4624 4625 4475 4474 4163 4626 4480 4622 4476 4475 4618 4627 4481 4626 4477 4476 4619 4628 4482 4627 4478 4477 4620 4629 4483 4628 4479 4478 4621 4630 4484 4629 4480 4479 4622 4631 4485 4630 4481 4480 4626 4343 4486 4631 4482 4481 4627 4632 4633 4341 4482 4628 4483 4634 4487 4341 4483 4629 4484 4488 4183 4634 4484 4630 4485 4635 4636 4637 4631 4486 4485 4638 4490 4489 4486 4343 4342 4350 4491 4638 4342 4341 4487 4639 4640 4348 4634 4183 4487 4354 4492 4348 4488 4184 4183 4641 4642 4352 4489 4490 4184 4358 4493 4352 4638 4491 4490 4643 4644 4356 4350 4349 4491 4645 4646 4647 4492 4349 4348 4495 4195 4494 4354 4353 4492 4648 4496 4645 4493 4353 4352 4649 4650 4651 4357 4493 4358 4365 4498 4497 4360 4357 4356 4649 4652 4363 4195 4360 4494 4653 4499 4652 4195 4495 4196 4502 4654 4655 4196 4496 4362 4656 4369 4500 4362 4497 4498 4371 4503 4656 4364 4498 4365 4501 4657 4370 4364 4363 4367 4658 4504 4657 4367 4499 4368 4659 4505 4658 4368 4500 4369 4660 4506 4659 4369 4656 4503 4661 4507 4660 4503 4371 4205 4662 4663 4664 4370 4206 4205 4512 4664 4665 4504 4373 4206 4666 4378 4509 4505 4374 4373 4511 4379 4666 4506 4375 4374 4381 4514 4511 4375 4507 4376 4513 4667 4380 4376 4508 4377 4668 4515 4667 4377 4509 4378 4669 4516 4668 4378 4666 4379 4670 4517 4669 4379 4511 4514 4521 4671 4672 4514 4381 4215 4673 4386 4518 4380 4216 4215 4520 4222 4673 4216 4515 4383 4519 4674 4522 4383 4516 4384 4675 4523 4674 4384 4517 4385 4676 4389 4523 4385 4518 4386 4525 4227 4676 4222 4386 4673 4677 4527 4524 4223 4222 4520 4678 4391 4527 4223 4522 4388 4529 140 4678 4389 4388 4523 4679 4680 4681 4227 4389 4676 4532 4394 4531 4228 4227 4525 4682 4683 4684 4391 4228 4527 4685 157 4533 4678 140 4391 151 155 4685 140 4529 4392 4686 4687 4688 4394 4392 4531 4536 143 4689 4394 4532 4395 4537 4689 4690 157 4395 4533 4686 4538 4690 155 157 4685 152 143 142 151 150 155 4235 4544 4403 4403 4543 4542 4538 4234 4400 144 143 4536 4542 4691 4540 4689 4537 4536 4692 4693 4543 4537 4690 4538 4406 4694 4546 4235 4686 4544 4695 4696 4697 4545 4546 4698 4540 4539 4239 4691 4542 4543 4547 4408 4698 4541 4540 4691 4548 4550 4409 4539 4694 4406 4548 4699 4700 3949 3951 4701 4405 4408 4407 4408 4545 4698 3951 4549 4701 4410 4550 4549 4411 4409 4550 4550 4702 4549 3814 4549 3951 3812 3950 4412 4252 4251 4551 4703 4704 4705 4412 4552 4413 4706 4552 4251 4707 4708 4253 4707 4255 4706 4708 4709 4256 4255 4707 4253 4415 4258 4710 4256 4253 4708 4711 4712 4713 4256 4709 4258 4714 4715 4716 4710 4258 4709 4263 4717 4718 4416 4415 4710 4718 4419 4261 4418 4414 4416 695 692 696 4417 4418 4717 4719 4420 682 4717 4263 4417 4720 4421 4719 4261 4263 4718 4563 4422 4720 684 4261 4419 4721 4423 4563 549 681 684 4566 4424 4721 682 4420 681 4722 4723 4724 4421 4420 4719 4570 4271 4569 4720 4422 4421 4722 4725 4571 4423 4422 4563 4726 4727 4728 4424 4423 4721 4430 4573 4572 4425 4424 4566 4726 4729 4428 4271 4425 4569 4730 4574 4729 4269 4271 4570 4731 4732 4733 4269 4571 4427 4434 4576 4575 4573 4427 4572 4731 4734 4433 4429 4573 4430 4734 4735 4577 4429 4428 4431 4735 4736 4578 4431 4574 4432 4737 4579 4736 4432 4575 4576 4738 4739 4740 4576 4434 4280 4583 4740 4741 4280 4433 4278 4742 4439 4581 4278 4577 4281 4582 4440 4742 4578 4436 4281 4443 4586 4582 4436 4579 4437 4585 4743 4441 4437 4580 4438 4743 4744 4444 4438 4581 4439 4744 4745 4587 4439 4742 4440 4745 4746 4588 4440 4582 4586 4747 4589 4746 4586 4443 4442 4591 4748 4749 4442 4441 4291 4750 4448 4590 4291 4444 4289 4450 4593 4750 4292 4289 4587 4592 4751 4449 4292 4588 4446 4751 4752 4594 4446 4589 4447 4753 4595 4752 4447 4590 4448 4754 4453 4595 4448 4750 4593 4596 4303 4754 4298 4593 4450 4598 4755 4599 4297 4298 4449 4756 4455 4599 4297 4594 4452 4600 4456 4756 4453 4452 4595 4757 4758 4759 4303 4453 4754 4604 4309 4603 4596 4301 4303 4757 4760 4605 4455 4301 4599 4606 4313 4605 4756 4456 4455 4761 4762 4763 4457 4456 4600 4764 4608 4607 4603 4309 4457 4462 4609 4764 4309 4604 4307 4765 4766 4460 4605 4313 4307 4767 4610 4460 4313 4606 4311 4466 4611 4767 4311 4607 4608 4768 4769 4770 4764 4609 4608 4771 4612 4464 4609 4462 4461 4772 4613 4771 4461 4460 4610 4773 4614 4772 4610 4767 4611 4774 4615 4773 4465 4611 4466 4774 4775 4616 4612 4465 4464 4775 4164 4617 4612 4771 4613 4618 4165 4776 4613 4772 4614 4619 4776 4777 4614 4773 4615 4620 4777 4778 4616 4615 4774 4621 4778 4779 4617 4616 4775 4621 4478 4620 4164 4163 4617 4779 4780 4622 4165 4618 4163 4780 4781 4626 4619 4618 4776 4782 4627 4781 4620 4619 4777 4624 4628 4782 4621 4620 4778 4783 4629 4624 4622 4621 4779 4784 4630 4783 4626 4622 4780 4785 4631 4784 4627 4626 4781 4632 4343 4785 4628 4627 4782 4786 4787 4788 4628 4624 4629 4789 4634 4633 4629 4783 4630 4790 4488 4789 4630 4784 4631 4791 4489 4790 4785 4343 4631 4635 4638 4791 4343 4632 4341 4639 4350 4635 4341 4633 4634 4792 4793 4640 4789 4488 4634 4641 4354 4640 4790 4489 4488 4794 4795 4642 4791 4638 4489 4643 4358 4642 4635 4350 4638 4796 4797 4644 4639 4348 4350 4798 4494 4644 4354 4348 4640 4645 4495 4798 4641 4352 4354 4799 4648 4647 4358 4352 4642 4800 4497 4648 4356 4358 4643 4649 4365 4800 4494 4356 4644 4651 4801 4652 4495 4494 4798 4654 4802 4803 4495 4645 4496 4804 4500 4653 4496 4648 4497 4502 4656 4804 4365 4497 4800 4655 4805 4501 4363 4365 4649 4805 4806 4657 4363 4652 4499 4807 4658 4806 4499 4653 4500 4808 4659 4807 4500 4804 4656 4809 4810 4811 4656 4502 4371 4663 4811 4812 4371 4501 4370 4813 4508 4661 4657 4504 4370 4662 4509 4813 4658 4505 4504 4512 4666 4662 4505 4659 4506 4665 4814 4510 4506 4660 4507 4814 4815 4513 4507 4661 4508 4815 4816 4667 4508 4813 4509 4817 4668 4816 4509 4662 4666 4818 4669 4817 4666 4512 4511 4671 4819 4820 4511 4510 4381 4821 4518 4670 4381 4513 4380 4521 4673 4821 4515 4380 4667 4672 4822 4519 4515 4668 4516 4822 4823 4674 4516 4669 4517 4824 4825 4826 4517 4670 4518 4526 4676 4675 4673 4518 4821 4824 4827 4524 4520 4673 4521 4828 4829 4830 4522 4520 4519 4530 4678 4677 4523 4522 4674 4828 4831 4528 4676 4523 4675 4832 4531 4528 4525 4676 4526 4679 4532 4832 4527 4525 4524 4833 4533 4679 4678 4527 4677 4682 4685 4833 4530 4529 4678 154 151 4682 4528 4531 4529 4834 4534 152 4832 4532 4531 4835 4689 153 4533 4532 4679 4687 4690 4835 4685 4533 4833 152 4534 153 151 4685 4682 4836 4837 4838 142 151 154 4544 4692 4543 4693 4691 4543 4686 4235 4538 143 153 4689 4691 4837 4541 4689 4835 4690 4541 4836 4694 4690 4687 4686 4839 4693 4840 4692 4544 4688 4695 4546 4841 4697 4698 4695 4541 4694 4539 4693 4837 4691 4699 4547 4697 4836 4541 4837 4700 4702 4548 4841 4546 4694 4546 4695 4698 4700 4842 4843 4408 4547 4409 4547 4698 4697 4701 4844 4845 4701 4551 3949 4550 4548 4702 4701 4702 4844 4549 4702 4701 3950 4251 4552 4248 4250 4252 4247 4250 4248 4552 4706 4255 4250 4846 4706 4708 4847 4555 4847 4707 4846 4555 4559 4709 4708 4707 4847 4713 4416 4710 4708 4555 4709 4418 4416 4712 4559 4710 4709 4717 4418 4848 4559 4713 4710 4718 4849 4561 4712 4416 4713 4561 550 4419 4848 4418 4712 548 4850 682 4717 4848 4849 690 4719 4850 4849 4718 4717 4564 4720 690 4419 4718 4561 4851 4852 4565 549 4419 550 4567 4721 4565 549 548 682 4853 4854 4568 4850 4719 682 4855 4569 4568 4720 4719 690 4722 4570 4855 4564 4563 4720 4724 4856 4725 4721 4563 4565 4857 4572 4725 4566 4721 4567 4726 4430 4857 4569 4566 4568 4728 4858 4729 4570 4569 4855 4732 4859 4860 4571 4570 4722 4861 4575 4730 4571 4725 4572 4731 4434 4861 4430 4572 4857 4733 4862 4734 4428 4430 4726 4862 4863 4735 4428 4729 4574 4863 4864 4736 4574 4730 4575 4739 4865 4866 4575 4861 4434 4867 4580 4737 4434 4731 4433 4738 4581 4867 4433 4734 4577 4583 4742 4738 4578 4577 4735 4741 4868 4584 4578 4736 4579 4868 4869 4585 4579 4737 4580 4869 4870 4743 4580 4867 4581 4870 4871 4744 4581 4738 4742 4871 4872 4745 4742 4583 4582 4872 4873 4746 4582 4584 4443 4748 4874 4875 4443 4585 4441 4876 4590 4747 4441 4743 4444 4591 4750 4876 4587 4444 4744 4749 4877 4592 4588 4587 4745 4877 4878 4751 4588 4746 4589 4878 4879 4752 4589 4747 4590 4880 4881 4882 4590 4876 4750 4597 4754 4753 4450 4750 4591 4880 4883 4598 4449 4450 4592 4884 4885 4886 4594 4449 4751 4601 4756 4755 4595 4594 4752 4885 4887 4602 4754 4595 4753 4888 4603 4602 4596 4754 4597 4757 4604 4888 4598 4599 4596 4889 4890 4891 4756 4599 4755 4892 4606 4760 4601 4600 4756 4892 4893 4607 4603 4600 4602 4762 4764 4893 4888 4604 4603 4765 4462 4762 4604 4757 4605 4894 4895 4896 4760 4606 4605 4897 4767 4766 4606 4892 4607 4898 4466 4897 4607 4893 4764 4898 4899 4464 4762 4462 4764 4769 4771 4899 4462 4765 4460 4900 4772 4769 4460 4766 4767 4901 4773 4900 4767 4897 4466 4902 4774 4901 4464 4466 4898 4902 4903 4775 4771 4464 4899 4903 4904 4164 4772 4771 4769 4904 4905 4165 4773 4772 4900 4905 4906 4776 4774 4773 4901 4906 4907 4777 4902 4775 4774 4907 4908 4778 4903 4164 4775 4908 4909 4779 4904 4165 4164 4909 4910 4780 4905 4776 4165 4910 4911 4781 4906 4777 4776 4911 4625 4782 4778 4777 4907 4912 4913 4914 4779 4778 4908 4912 4783 4623 4780 4779 4909 4915 4784 4912 4781 4780 4910 4916 4785 4915 4782 4781 4911 4917 4632 4916 4624 4782 4625 4917 4918 4633 4624 4623 4783 4787 4789 4918 4783 4912 4784 4919 4790 4787 4784 4915 4785 4636 4791 4919 4785 4916 4632 4920 4921 4637 4632 4917 4633 4792 4639 4637 4633 4918 4789 4922 4923 4924 4787 4790 4789 4794 4641 4793 4919 4791 4790 4925 4926 4927 4636 4635 4791 4796 4643 4795 4637 4639 4635 4928 4929 4930 4792 4640 4639 4646 4798 4797 4793 4641 4640 4929 4931 4647 4794 4642 4641 4932 4933 4934 4643 4642 4795 4650 4800 4799 4796 4644 4643 4932 4935 4651 4798 4644 4797 4935 4936 4801 4645 4798 4646 4937 4653 4801 4645 4647 4648 4654 4804 4937 4800 4648 4799 4803 4938 4655 4649 4800 4650 4938 4939 4805 4652 4649 4651 4939 4940 4806 4652 4801 4653 4941 4942 4943 4653 4937 4804 4810 4943 4944 4804 4654 4502 4945 4660 4808 4502 4655 4501 4809 4661 4945 4501 4805 4657 4663 4813 4809 4658 4657 4806 4812 4946 4664 4658 4807 4659 4946 4947 4665 4659 4808 4660 4947 4948 4814 4660 4945 4661 4948 4949 4815 4661 4809 4813 4949 4950 4816 4813 4663 4662 4950 4951 4817 4662 4664 4512 4819 4952 4953 4512 4665 4510 4954 4670 4818 4510 4814 4513 4671 4821 4954 4667 4513 4815 4820 4955 4672 4668 4667 4816 4955 4956 4822 4668 4817 4669 4957 4825 4958 4669 4818 4670 4959 4675 4823 4670 4954 4821 4824 4526 4959 4521 4821 4671 4826 4960 4827 4519 4521 4672 4961 4677 4827 4674 4519 4822 4828 4530 4961 4675 4674 4823 4830 4962 4831 4526 4675 4959 4680 4832 4831 4824 4524 4526 4963 4964 4681 4677 4524 4827 4683 4833 4681 4961 4530 4677 4965 4966 4684 4828 4528 4530 4834 154 4684 4831 4832 4528 161 147 4967 4679 4832 4680 146 4835 4535 4833 4679 4681 4968 4687 146 4683 4682 4833 4969 4688 4968 4684 154 4682 4535 4534 4970 154 4834 152 4692 4840 4693 4693 4839 4837 4688 4544 4686 153 4535 4835 4971 4972 4696 4835 146 4687 4836 4973 4841 4687 4968 4688 4839 4974 4975 4692 4969 4840 4696 4695 4976 4697 4696 4977 4836 4841 4694 4838 4837 4839 4842 4699 4977 4838 4973 4836 4977 4696 4972 4841 4976 4695 4700 4843 4844 4843 4978 4979 4547 4699 4548 4699 4697 4977 4252 4845 4980 4845 4551 4701 4702 4700 4844 4845 4844 4981 4252 4551 4845 4250 4706 4251 4554 4247 4246 4982 4983 4984 4706 4846 4707 4247 4985 4846 4983 4986 4987 4985 4556 4847 4988 4989 4990 4555 4847 4556 4991 4992 4988 4555 4557 4559 4716 4848 4712 4559 4558 4713 4849 4848 4715 4558 4711 4713 4993 4994 4995 4711 4716 4712 550 4560 691 4848 4716 4715 692 688 4850 4849 4715 4562 4996 4997 689 4562 4561 4849 4851 4564 689 4561 4560 550 4998 4999 5000 691 548 550 4853 4567 4852 548 692 4850 4999 5001 4854 688 690 4850 4723 4855 4854 689 4564 690 5002 5003 4724 4851 4565 4564 5004 5005 5006 4567 4565 4852 4727 4857 4856 4853 4568 4567 5005 5007 4728 4855 4568 4854 5008 5009 4859 4722 4855 4723 5010 4730 4858 4725 4722 4724 4732 4861 5010 4857 4725 4856 4860 5011 4733 4726 4857 4727 5011 5012 4862 4729 4726 4728 5012 5013 4863 4730 4729 4858 5014 4865 5015 4730 5010 4861 5016 4737 4864 4861 4732 4731 4739 4867 5016 4734 4731 4733 4866 5017 4740 4735 4734 4862 5017 5018 4741 4736 4735 4863 5018 5019 4868 4736 4864 4737 5019 5020 4869 4737 5016 4867 5020 5021 4870 4867 4739 4738 5021 5022 4871 4738 4740 4583 5022 5023 4872 4583 4741 4584 5024 5025 4874 4584 4868 4585 5026 4747 4873 4585 4869 4743 4748 4876 5026 4744 4743 4870 4875 5027 4749 4745 4744 4871 5027 5028 4877 4746 4745 4872 5028 5029 4878 4746 4873 4747 5030 4881 5031 4747 5026 4876 5032 4753 4879 4876 4748 4591 4880 4597 5032 4592 4591 4749 4882 5033 4883 4751 4592 4877 4883 5034 4755 4752 4751 4878 4885 4601 5034 4753 4752 4879 4884 5035 4887 4597 4753 5032 4758 4888 4887 4880 4598 4597 5036 5037 4759 4883 4755 4598 4759 5038 4760 4601 4755 5034 4890 4892 5038 4885 4602 4601 4890 4763 4893 4602 4887 4888 5039 5040 4761 4758 4757 4888 5041 4765 4761 4757 4759 4760 5041 5042 4766 5038 4892 4760 4895 4897 5042 4892 4890 4893 5043 4898 4895 4893 4763 4762 5043 4770 4899 4762 4761 4765 5044 5045 5046 4765 5041 4766 5047 4900 4768 4766 5042 4897 5048 4901 5047 4897 4895 4898 5049 4902 5048 4899 4898 5043 5049 5050 4903 4769 4899 4770 5050 5051 4904 4900 4769 4768 5051 5052 4905 4901 4900 5047 5052 5053 4906 4902 4901 5048 5053 5054 4907 5049 4903 4902 5054 5055 4908 5050 4904 4903 5055 5056 4909 5051 4905 4904 5056 5057 4910 5052 4906 4905 5057 5058 4911 5053 4907 4906 5058 5059 4625 5054 4908 4907 5059 4913 4623 5055 4909 4908 5060 5061 5062 4910 4909 5056 5063 4915 4914 4911 4910 5057 5064 4916 5063 4625 4911 5058 5065 4917 5064 4623 4625 5059 5065 4788 4918 4912 4623 4913 5066 5067 5068 4912 4914 4915 5069 4919 4786 4915 5063 4916 4920 4636 5069 4916 5064 4917 5070 5071 5072 4917 5065 4918 5073 4792 4921 4918 4788 4787 5073 5074 4793 4786 4919 4787 4923 4794 5074 4919 5069 4636 4923 5075 4795 4920 4637 4636 4926 4796 5075 4921 4792 4637 4926 5076 4797 5073 4793 4792 4929 4646 5076 5074 4794 4793 4928 5077 4931 4923 4795 4794 5078 4799 4931 4796 4795 5075 4932 4650 5078 4926 4797 4796 4934 5079 4935 4646 4797 5076 5080 5081 5082 4647 4646 4929 4802 4937 4936 4931 4799 4647 5081 5083 4803 4650 4799 5078 5083 5084 4938 4651 4650 4932 5084 5085 4939 4801 4651 4935 5086 5087 4942 4801 4936 4937 4940 5088 4807 4937 4802 4654 4941 4808 5088 4654 4803 4655 4810 4945 4941 4805 4655 4938 4944 5089 4811 4806 4805 4939 5089 5090 4812 4807 4806 4940 5090 5091 4946 4807 5088 4808 5091 5092 4947 4808 4941 4945 5092 5093 4948 4945 4810 4809 5093 5094 4949 4809 4811 4663 5095 5096 5097 4663 4812 4664 5098 4952 5096 4664 4946 4665 5099 4818 4951 4665 4947 4814 4819 4954 5099 4815 4814 4948 4953 5100 4820 4816 4815 4949 5100 5101 4955 4817 4816 4950 5101 5102 4956 4817 4951 4818 4956 5103 4823 4818 5099 4954 4825 4959 5103 4671 4954 4819 4957 5104 4826 4672 4671 4820 5105 5106 5107 4822 4672 4955 4829 4961 4960 4956 4823 4822 5106 5108 4830 4959 4823 5103 5109 5110 5111 4824 4959 4825 4963 4680 4962 4826 4827 4824 5112 5113 5114 4961 4827 4960 4965 4683 4964 4829 4828 4961 5115 5116 5117 4830 4831 4828 5118 4834 4966 4962 4680 4831 5118 4970 4534 4963 4681 4680 4970 147 4535 4683 4681 4964 158 4968 145 4684 4683 4965 5119 4969 158 4834 4684 4966 4970 4967 147 5118 4534 4834 4840 4974 4839 4975 4838 4839 4969 4692 4688 4535 147 146 4838 5120 4973 4968 146 145 4973 5121 4976 4969 4968 158 5122 4975 5123 4840 5119 4974 4977 4972 5124 5124 4978 4842 4973 4976 4841 5120 4838 4975 4972 5125 5124 5121 4973 5120 4979 4981 4843 4976 4971 4696 5126 5127 4979 5128 4980 5129 4699 4842 4700 4977 5124 4842 4248 4980 5128 4845 4981 4980 4844 4843 4981 4981 5129 4980 4252 4980 4248 4250 4247 4846 5130 4553 4554 4704 4553 5130 4846 4985 4847 4553 5131 4985 5132 4989 4557 5132 4556 5131 4989 4992 4558 4556 5132 4557 5133 4716 4711 4558 4557 4989 5134 5135 5136 4558 4992 4711 4562 4715 4994 4992 5133 4711 4560 4993 697 5133 4714 4716 5137 704 702 4714 4994 4715 695 4996 688 4994 4993 4562 5138 5139 5140 4993 4560 4562 5141 4851 4997 697 691 4560 5141 5142 4852 696 692 691 4999 4853 5142 692 695 688 5143 5144 5145 4996 689 688 5002 4723 5001 4997 4851 689 5144 5146 5003 5141 4852 4851 5003 5147 4856 4853 4852 5142 5005 4727 5147 4999 4854 4853 5004 5148 5007 4723 4854 5001 5007 5149 4858 4724 4723 5002 5149 4859 5010 5003 4856 4724 5009 5150 4860 4727 4856 5147 5150 5151 5011 4728 4727 5005 5151 5152 5012 4858 4728 5007 5153 5154 5015 5010 4858 5149 5013 5155 4864 5010 4859 4732 4865 5016 5155 4733 4732 4860 5014 5156 4866 4862 4733 5011 5156 5157 5017 4863 4862 5012 5157 5158 5018 4864 4863 5013 5158 5159 5019 4864 5155 5016 5159 5160 5020 5016 4865 4739 5160 5161 5021 4739 4866 4740 5162 5163 5164 4740 5017 4741 5163 5165 5024 4741 5018 4868 5023 5166 4873 4868 5019 4869 4874 5026 5166 4870 4869 5020 5025 5167 4875 4871 4870 5021 5167 5168 5027 4872 4871 5022 5168 5169 5028 4873 4872 5023 5170 5171 5031 5026 4873 5166 5029 5172 4879 5026 4874 4748 4881 5032 5172 4749 4748 4875 5030 5173 4882 4877 4749 5027 5174 5175 5176 4878 4877 5028 5033 4886 5034 5029 4879 4878 5176 5177 4884 5032 4879 5172 5178 5179 5180 4880 5032 4881 5035 5036 4758 4882 4883 4880 5180 5181 5037 5033 5034 4883 5037 4891 5038 4886 4885 5034 5182 5183 4889 4884 4887 4885 4889 5039 4763 4887 5035 4758 5184 5185 5186 5036 4759 4758 5187 5041 5040 4759 5037 5038 5187 4896 5042 5038 4891 4890 5188 5189 4894 4890 4889 4763 5190 5043 4894 4763 5039 4761 5190 5191 4770 4761 5040 5041 5191 5192 4768 5041 5187 5042 5045 5047 5192 5042 4896 4895 5193 5048 5045 4895 4894 5043 5194 5049 5193 4770 5043 5190 5194 5195 5050 4768 4770 5191 5195 5196 5051 5047 4768 5192 5196 5197 5052 5048 5047 5045 5197 5198 5053 5049 5048 5193 5198 5199 5054 5194 5050 5049 5199 5200 5055 5195 5051 5050 5200 5201 5056 5196 5052 5051 5201 5202 5057 5197 5053 5052 5202 5203 5058 5198 5054 5053 5203 5204 5059 5199 5055 5054 5204 5205 4913 5200 5056 5055 5205 5206 4914 5057 5056 5201 5207 5063 5206 5058 5057 5202 5208 5064 5207 5059 5058 5203 5209 5065 5208 4913 5059 5204 5209 5210 4788 4914 4913 5205 5210 5211 4786 4914 5206 5063 5067 5069 5211 5063 5207 5064 5067 5212 4920 5064 5208 5065 5212 5213 4921 5065 5209 4788 5071 5073 5213 4788 5210 4786 5071 4924 5074 4786 5211 5069 5214 5215 4922 5069 5067 4920 4922 4927 5075 4920 5212 4921 5216 5217 4925 5213 5073 4921 4925 4930 5076 5073 5071 5074 5218 5219 4928 4924 4923 5074 5220 5221 5222 4922 5075 4923 5077 4933 5078 4927 4926 5075 5222 5223 4934 4925 5076 4926 5224 5225 5082 4929 5076 4930 5079 5226 4936 4931 4929 4928 5081 4802 5226 5077 5078 4931 5080 5227 5083 4932 5078 4933 5227 5228 5084 4935 4932 4934 5229 5230 5086 4936 4935 5079 5085 5231 4940 4936 5226 4802 5231 4942 5088 4803 4802 5081 5087 5232 4943 4938 4803 5083 5232 5233 4944 4939 4938 5084 5233 5234 5089 4940 4939 5085 5234 5235 5090 5088 4940 5231 5235 5236 5091 5088 4942 4941 5236 5237 5092 4941 4943 4810 5238 5239 5240 4810 4944 4811 5239 5241 5095 4811 5089 4812 5094 5242 4950 4812 5090 4946 5242 5097 4951 4946 5091 4947 4952 5099 5097 4948 4947 5092 5098 5243 4953 4949 4948 5093 5243 5244 5100 4950 4949 5094 5244 5245 5101 4951 4950 5242 5246 5247 5248 4951 5097 5099 5102 4958 5103 4819 5099 4952 5248 5249 4957 4820 4819 4953 5249 5250 5104 4955 4820 5100 5104 5251 4960 4956 4955 5101 5106 4829 5251 5102 5103 4956 5105 5252 5108 4825 5103 4958 5108 5253 4962 4826 4825 4957 5110 4963 5253 5104 4960 4826 5110 5254 4964 4829 4960 5251 5113 4965 5254 5106 4830 4829 5113 5255 4966 5108 4962 4830 5116 5118 5255 5253 4963 4962 5116 4967 4970 4963 5110 4964 5256 5257 161 5254 4965 4964 5258 163 160 5113 4966 4965 165 5119 160 5255 5118 4966 161 4967 5256 5116 4970 5118 4974 5123 4975 5122 5120 4975 5119 4840 4969 145 147 161 5259 5121 5120 145 159 158 5121 5260 4971 5119 158 160 5261 5122 5262 5123 4974 165 5125 4972 5263 5264 5124 5125 5121 4971 4976 5259 5120 5122 5126 4978 5264 5259 5260 5121 5264 5125 5265 4971 5263 4972 4979 5127 5129 5127 5266 5267 4842 4978 4843 4978 5124 5264 4554 5128 5268 4246 4248 5128 4981 4979 5129 5128 5129 5269 4554 4246 5128 4247 4553 4985 4705 4704 5130 4703 4986 4704 4985 5131 4556 4704 5270 5131 5271 5272 5273 4990 5132 5270 5274 5275 5276 4989 5132 4990 5136 4714 5133 4989 4988 4992 4994 4714 5135 5133 4992 4991 5277 5278 5279 4991 5136 5133 697 5280 702 5135 4714 5136 703 5281 694 4994 5135 4995 694 5282 4996 4993 4995 5280 5282 5283 4997 697 4993 5280 5139 5141 5283 697 702 696 5139 5000 5142 696 693 695 5284 5285 4998 695 694 4996 4998 5286 5001 5282 4997 4996 5144 5002 5286 5283 5141 4997 5287 5288 5289 5139 5142 5141 5146 5006 5147 5000 4999 5142 5289 5290 5004 4998 5001 4999 5291 5292 5293 5002 5001 5286 5148 5008 5149 5144 5003 5002 5009 5293 5294 5146 5147 5003 5294 5295 5150 5005 5147 5006 5295 5296 5151 5007 5005 5004 5297 5298 5153 5149 5007 5148 5152 5299 5013 4859 5149 5008 5299 5015 5155 4860 4859 5009 5014 5154 5300 5011 4860 5150 5300 5301 5156 5012 5011 5151 5301 5302 5157 5013 5012 5152 5302 5303 5158 5155 5013 5299 5303 5304 5159 4865 5155 5015 5305 5306 5307 4865 5014 4866 5306 5308 5162 4866 5156 5017 5161 5309 5022 5017 5157 5018 5309 5164 5023 5018 5158 5019 5164 5024 5166 5020 5019 5159 5025 5165 5310 5021 5020 5160 5310 5311 5167 5022 5021 5161 5311 5312 5168 5023 5022 5309 5312 5313 5169 5166 5023 5164 5169 5314 5029 4874 5166 5024 5314 5031 5172 4875 4874 5025 5171 5315 5030 5027 4875 5167 5315 5316 5173 5028 5027 5168 5173 5317 5033 5029 5028 5169 5317 5176 4886 5314 5172 5029 5175 5318 5177 4881 5172 5031 5177 5319 5035 4882 4881 5030 5319 5180 5036 5173 5033 4882 5320 5321 5322 5317 4886 5033 5181 5182 4891 5176 4884 4886 5323 5324 5325 5177 5035 4884 5183 5326 5039 5035 5319 5036 5326 5327 5040 5180 5037 5036 5185 5187 5327 5037 5181 4891 5185 5188 4896 4891 5182 4889 5328 5329 5330 4889 5183 5039 5331 5190 5189 5039 5326 5040 5331 5332 5191 5040 5327 5187 5332 5046 5192 4896 5187 5185 5333 5334 5335 4896 5188 4894 5336 5193 5044 4894 5189 5190 5337 5194 5336 5191 5190 5331 5337 5338 5195 5192 5191 5332 5338 5339 5196 5045 5192 5046 5339 5340 5197 5193 5045 5044 5340 5341 5198 5194 5193 5336 5341 5342 5199 5337 5195 5194 5342 5343 5200 5338 5196 5195 5343 5344 5201 5339 5197 5196 5344 5345 5202 5340 5198 5197 5345 5346 5203 5341 5199 5198 5346 5347 5204 5342 5200 5199 5347 5348 5205 5343 5201 5200 5348 5349 5206 5344 5202 5201 5349 5350 5207 5203 5202 5345 5060 5208 5350 5204 5203 5346 5351 5209 5060 5205 5204 5347 5351 5352 5210 5206 5205 5348 5352 5068 5211 5207 5206 5349 5353 5354 5066 5207 5350 5208 5066 5355 5212 5208 5060 5209 5355 5072 5213 5210 5209 5351 5356 5357 5070 5210 5352 5211 5070 5214 4924 5211 5068 5067 5358 5359 5360 5067 5066 5212 5215 5216 4927 5212 5355 5213 5361 5362 5363 5072 5071 5213 5217 5218 4930 5071 5070 4924 5363 5364 5219 5214 4922 4924 5219 5365 5077 5215 4927 4922 5365 5222 4933 5216 4925 4927 5221 5366 5223 5217 4930 4925 5223 5367 5079 4928 4930 5218 5367 5082 5226 5219 5077 4928 5225 5368 5080 5365 4933 5077 5368 5369 5227 4934 4933 5222 5370 5371 5229 5079 4934 5223 5228 5372 5085 5226 5079 5367 5372 5086 5231 5081 5226 5082 5087 5230 5373 5083 5081 5080 5373 5374 5232 5084 5083 5227 5374 5375 5233 5085 5084 5228 5375 5376 5234 5231 5085 5372 5376 5377 5235 4942 5231 5086 5378 5379 5380 4942 5087 4943 5379 5381 5238 4943 5232 4944 5237 5382 5093 4944 5233 5089 5382 5240 5094 5089 5234 5090 5240 5095 5242 5091 5090 5235 5096 5241 5383 5092 5091 5236 5383 5384 5098 5093 5092 5237 5384 5385 5243 5094 5093 5382 5385 5386 5244 5242 5094 5240 5387 5388 5246 5097 5242 5095 5245 5389 5102 5097 5096 4952 5389 5248 4958 4953 4952 5098 5247 5390 5249 5100 4953 5243 5391 5392 5393 5101 5100 5244 5250 5107 5251 5245 5102 5101 5393 5394 5105 5389 4958 5102 5395 5396 5397 4957 4958 5248 5252 5111 5253 5249 5104 4957 5397 5398 5109 5250 5251 5104 5109 5114 5254 5107 5106 5251 5399 5400 5112 5105 5108 5106 5112 5117 5255 5108 5252 5253 5401 5402 5115 5111 5110 5253 5115 5256 4967 5110 5109 5254 5403 5404 164 5114 5113 5254 5258 159 5257 5255 5113 5112 5405 5257 5256 5116 5255 5117 5262 5122 5123 5115 4967 5116 5261 5259 5122 5260 5259 5406 165 4974 5119 5257 159 161 5263 5260 5407 159 5258 160 5261 5408 5409 160 163 165 5125 5410 5265 5262 5123 166 5264 5265 5411 5412 5413 5267 5260 5263 4971 5406 5259 5261 5266 5126 5411 5407 5260 5406 5267 5269 5127 5263 5410 5125 5267 5414 5412 5413 5415 5268 4978 5126 4979 5126 5264 5411 5130 5268 5415 5128 5269 5268 5129 5127 5269 5269 5413 5268 4554 5268 5130 4553 4704 5131 4987 4986 4703 5416 5417 5418 5131 5270 5132 5419 5270 4986 5420 5421 4988 5420 4990 5419 5421 5422 4991 4988 4990 5420 5423 5424 5425 4991 4988 5421 4995 5135 5426 4991 5422 5136 5280 4995 5427 5422 5134 5136 710 709 719 5135 5134 5426 5428 5429 5430 4995 5426 5427 5281 5431 5282 5280 5427 5137 5431 5140 5283 5280 5137 702 5432 5433 5138 702 704 693 5138 5284 5000 693 703 694 5434 5435 5285 694 5281 5282 5285 5145 5286 5282 5431 5283 5143 5436 5437 5140 5139 5283 5143 5438 5146 5138 5000 5139 5438 5289 5006 5284 4998 5000 5288 5439 5290 5285 5286 4998 5290 5440 5148 5145 5144 5286 5440 5293 5008 5143 5146 5144 5294 5292 5441 5438 5006 5146 5441 5442 5295 5004 5006 5289 5443 5444 5297 5148 5004 5290 5296 5445 5152 5008 5148 5440 5445 5153 5299 5293 5009 5008 5154 5298 5446 5150 5009 5294 5300 5446 5447 5151 5150 5295 5447 5448 5301 5152 5151 5296 5448 5449 5302 5299 5152 5445 5450 5451 5452 5015 5299 5153 5451 5453 5305 5014 5015 5154 5304 5454 5160 5014 5300 5156 5454 5307 5161 5156 5301 5157 5307 5162 5309 5158 5157 5302 5163 5308 5455 5159 5158 5303 5165 5455 5456 5160 5159 5304 5310 5456 5457 5161 5160 5454 5457 5458 5311 5309 5161 5307 5459 5460 5461 5164 5309 5162 5460 5462 5463 5024 5164 5163 5313 5170 5314 5165 5025 5024 5171 5463 5464 5167 5025 5310 5315 5464 5465 5168 5167 5311 5466 5467 5468 5169 5168 5312 5316 5174 5317 5313 5314 5169 5175 5468 5469 5170 5031 5314 5469 5470 5318 5171 5030 5031 5318 5178 5319 5315 5173 5030 5179 5471 5472 5316 5317 5173 5179 5473 5181 5174 5176 5317 5473 5322 5182 5175 5177 5176 5322 5474 5183 5318 5319 5177 5474 5325 5326 5319 5178 5180 5325 5186 5327 5180 5179 5181 5475 5476 5184 5181 5473 5182 5184 5477 5188 5182 5322 5183 5477 5478 5189 5183 5474 5326 5329 5331 5478 5326 5325 5327 5329 5479 5332 5327 5186 5185 5479 5480 5046 5188 5185 5184 5480 5481 5044 5188 5477 5189 5334 5336 5481 5189 5478 5331 5482 5337 5334 5332 5331 5329 5482 5483 5338 5046 5332 5479 5483 5484 5339 5044 5046 5480 5484 5485 5340 5336 5044 5481 5485 5486 5341 5334 5337 5336 5486 5487 5342 5482 5338 5337 5487 5488 5343 5483 5339 5338 5488 5489 5344 5484 5340 5339 5489 5490 5345 5485 5341 5340 5490 5491 5346 5486 5342 5341 5491 5492 5347 5487 5343 5342 5492 5493 5348 5488 5344 5343 5493 5494 5349 5489 5345 5344 5494 5061 5350 5490 5346 5345 5495 5496 5497 5347 5346 5491 5498 5351 5062 5348 5347 5492 5498 5499 5352 5349 5348 5493 5499 5353 5068 5350 5349 5494 5500 5501 5502 5350 5061 5060 5354 5503 5355 5060 5062 5351 5503 5356 5072 5352 5351 5498 5504 5505 5506 5352 5499 5068 5357 5507 5214 5068 5353 5066 5507 5508 5215 5066 5354 5355 5508 5360 5216 5355 5503 5072 5360 5509 5217 5356 5070 5072 5509 5363 5218 5070 5357 5214 5510 5511 5512 5507 5215 5214 5364 5220 5365 5215 5508 5216 5221 5512 5513 5360 5217 5216 5514 5515 5516 5509 5218 5217 5366 5224 5367 5363 5219 5218 5225 5516 5517 5364 5365 5219 5517 5518 5368 5220 5222 5365 5519 5520 5370 5223 5222 5221 5369 5521 5228 5367 5223 5366 5521 5229 5372 5224 5082 5367 5230 5371 5522 5080 5082 5225 5373 5522 5523 5227 5080 5368 5523 5524 5374 5228 5227 5369 5524 5525 5375 5372 5228 5521 5526 5527 5528 5086 5372 5229 5527 5529 5378 5087 5086 5230 5377 5530 5236 5087 5373 5232 5530 5380 5237 5232 5374 5233 5380 5238 5382 5234 5233 5375 5239 5381 5531 5235 5234 5376 5241 5531 5532 5236 5235 5377 5383 5532 5533 5237 5236 5530 5533 5534 5384 5382 5237 5380 5534 5535 5385 5240 5382 5238 5536 5537 5387 5095 5240 5239 5386 5538 5245 5096 5095 5241 5538 5246 5389 5098 5096 5383 5247 5388 5539 5243 5098 5384 5539 5540 5390 5244 5243 5385 5390 5541 5250 5245 5244 5386 5541 5393 5107 5538 5389 5245 5394 5392 5542 5246 5248 5389 5394 5543 5252 5249 5248 5247 5543 5397 5111 5390 5250 5249 5396 5544 5398 5541 5107 5250 5398 5399 5114 5107 5393 5105 5545 5546 5400 5394 5252 5105 5400 5401 5117 5252 5543 5111 5547 5548 5402 5397 5109 5111 5402 5405 5256 5109 5398 5114 5405 5549 5257 5399 5112 5114 164 5258 5549 5112 5400 5117 5550 173 5551 5117 5401 5115 5552 5549 5405 5402 5256 5115 5262 5408 5261 5261 5409 5406 166 5123 165 5257 5549 5258 5406 5553 5407 5258 164 163 5407 5554 5410 166 163 162 5555 5409 5556 5408 5262 170 5557 5265 5558 5559 5411 5557 5407 5410 5263 5409 5553 5406 5414 5266 5559 5553 5554 5407 5559 5557 5560 5558 5265 5410 5265 5557 5411 5412 5561 5562 5126 5266 5127 5266 5411 5559 5415 5563 5564 4703 4705 5415 5269 5267 5413 5413 5563 5415 5130 5415 4705 4704 4986 5270 4984 4983 4987 4982 5272 4983 5270 5419 4990 4983 5565 5419 5421 5566 5274 5566 5420 5565 5274 5567 5422 5421 5420 5566 5426 5134 5568 5422 5421 5274 5279 5427 5426 5422 5567 5134 5137 5427 5278 5568 5134 5567 707 5569 703 5279 5426 5568 5569 5570 5281 5279 5278 5427 5570 5430 5431 5278 706 5137 5430 5432 5140 704 5137 706 5571 5572 5573 704 707 703 5433 5434 5284 703 5569 5281 5574 5575 5576 5281 5570 5431 5435 5436 5145 5431 5430 5140 5437 5574 5577 5432 5138 5140 5437 5287 5438 5138 5433 5284 5288 5578 5579 5434 5285 5284 5580 5581 5582 5435 5145 5285 5439 5291 5440 5145 5436 5143 5292 5580 5583 5437 5438 5143 5441 5583 5584 5287 5289 5438 5443 5585 5586 5290 5289 5288 5442 5587 5296 5440 5290 5439 5587 5297 5445 5291 5293 5440 5298 5444 5588 5292 5294 5293 5446 5588 5589 5295 5294 5441 5447 5589 5590 5296 5295 5442 5591 5592 5593 5445 5296 5587 5450 5591 5594 5153 5445 5297 5449 5595 5303 5154 5153 5298 5595 5452 5304 5300 5154 5446 5452 5305 5454 5301 5300 5447 5306 5453 5596 5302 5301 5448 5308 5596 5597 5303 5302 5449 5455 5597 5598 5304 5303 5595 5456 5598 5599 5454 5304 5452 5457 5599 5600 5307 5454 5305 5459 5601 5602 5162 5307 5306 5458 5603 5312 5163 5162 5308 5603 5461 5313 5165 5163 5455 5461 5463 5170 5456 5310 5165 5464 5462 5604 5311 5310 5457 5465 5604 5605 5312 5311 5458 5465 5606 5316 5313 5312 5603 5606 5468 5174 5461 5170 5313 5469 5467 5607 5463 5171 5170 5608 5609 5610 5464 5315 5171 5470 5471 5178 5465 5316 5315 5472 5608 5611 5606 5174 5316 5472 5320 5473 5174 5468 5175 5321 5612 5613 5469 5318 5175 5321 5323 5474 5318 5470 5178 5324 5614 5615 5178 5471 5179 5324 5475 5186 5179 5472 5473 5616 5617 5476 5473 5320 5322 5476 5618 5477 5322 5321 5474 5618 5330 5478 5325 5474 5323 5619 5620 5328 5325 5324 5186 5328 5621 5479 5186 5475 5184 5621 5622 5480 5477 5184 5476 5622 5335 5481 5478 5477 5618 5623 5624 5625 5478 5330 5329 5333 5626 5482 5479 5329 5328 5626 5627 5483 5480 5479 5621 5627 5628 5484 5481 5480 5622 5628 5629 5485 5334 5481 5335 5629 5630 5486 5333 5482 5334 5630 5631 5487 5626 5483 5482 5631 5632 5488 5627 5484 5483 5632 5633 5489 5628 5485 5484 5633 5634 5490 5629 5486 5485 5634 5635 5491 5630 5487 5486 5635 5636 5492 5631 5488 5487 5636 5637 5493 5632 5489 5488 5637 5638 5494 5633 5490 5489 5638 5639 5061 5634 5491 5490 5639 5640 5062 5492 5491 5635 5641 5498 5640 5493 5492 5636 5641 5642 5499 5494 5493 5637 5642 5643 5353 5061 5494 5638 5643 5644 5354 5061 5639 5062 5644 5502 5503 5062 5640 5498 5502 5645 5356 5499 5498 5641 5645 5646 5357 5499 5642 5353 5646 5506 5507 5353 5643 5354 5506 5358 5508 5503 5354 5644 5359 5647 5648 5503 5502 5356 5359 5361 5509 5356 5645 5357 5362 5649 5650 5357 5646 5507 5362 5651 5364 5506 5508 5507 5651 5512 5220 5508 5358 5360 5513 5511 5652 5359 5509 5360 5513 5653 5366 5361 5363 5509 5653 5516 5224 5362 5364 5363 5517 5515 5654 5651 5220 5364 5519 5655 5656 5512 5221 5220 5518 5657 5369 5366 5221 5513 5657 5370 5521 5653 5224 5366 5371 5520 5658 5516 5225 5224 5522 5658 5659 5368 5225 5517 5523 5659 5660 5369 5368 5518 5660 5661 5524 5521 5369 5657 5526 5662 5663 5229 5521 5370 5525 5664 5376 5230 5229 5371 5664 5528 5377 5373 5230 5522 5528 5378 5530 5374 5373 5523 5379 5529 5665 5375 5374 5524 5381 5665 5666 5376 5375 5525 5531 5666 5667 5377 5376 5664 5532 5667 5668 5530 5377 5528 5533 5668 5669 5380 5530 5378 5534 5669 5670 5238 5380 5379 5536 5671 5672 5239 5238 5381 5535 5673 5386 5241 5239 5531 5673 5387 5538 5532 5383 5241 5388 5537 5674 5533 5384 5383 5539 5674 5675 5385 5384 5534 5676 5677 5678 5386 5385 5535 5540 5391 5541 5673 5538 5386 5392 5676 5679 5387 5246 5538 5542 5679 5680 5388 5247 5246 5542 5395 5543 5539 5390 5247 5396 5681 5682 5540 5541 5390 5683 5684 5685 5391 5393 5541 5544 5545 5399 5393 5392 5394 5686 5687 5688 5542 5543 5394 5546 5547 5401 5543 5395 5397 5689 5690 5691 5396 5398 5397 5548 5552 5405 5398 5544 5399 5552 5403 5549 5399 5545 5400 5404 168 5692 5400 5546 5401 5404 174 162 5547 5402 5401 5403 5552 5689 5402 5548 5405 5408 5556 5409 5555 5553 5409 170 5262 166 5549 5403 164 5553 5693 5554 164 5404 162 5554 5694 5558 170 162 174 5550 5555 182 5556 5408 175 5560 5557 5695 5559 5560 5696 5554 5558 5410 5555 5693 5553 5561 5414 5696 5693 5694 5554 5696 5560 5697 5558 5695 5557 5412 5562 5563 5562 5698 5699 5266 5414 5267 5414 5559 5696 4987 5564 5700 5564 4703 5415 5413 5412 5563 5564 5563 5701 4987 4703 5564 4983 5419 4986 5273 5272 4982 5702 5703 5704 5419 5565 5420 5272 5705 5565 5706 5707 5708 5705 5275 5566 5276 5425 5567 5274 5566 5275 5709 5279 5568 5567 5274 5276 5710 5711 5712 5567 5425 5568 706 5278 711 5709 5568 5425 710 5713 5569 5277 5279 5709 5713 5428 5570 711 5278 5277 5714 5715 5716 711 709 706 5429 5717 5432 707 706 709 5717 5572 5433 707 710 5569 5572 5571 5434 5569 5713 5570 5571 5575 5435 5570 5428 5430 5575 5574 5436 5430 5429 5432 5718 5719 5720 5717 5433 5432 5577 5578 5287 5433 5572 5434 5719 5579 5578 5571 5435 5434 5579 5581 5439 5575 5436 5435 5581 5580 5291 5436 5574 5437 5721 5583 5580 5577 5287 5437 5722 5586 5723 5578 5288 5287 5584 5585 5442 5439 5288 5579 5585 5443 5587 5581 5291 5439 5724 5444 5443 5580 5292 5291 5725 5588 5444 5583 5441 5292 5726 5727 5728 5442 5441 5584 5729 5593 5727 5587 5442 5585 5590 5592 5448 5297 5587 5443 5592 5591 5449 5298 5297 5444 5591 5450 5595 5588 5446 5298 5730 5451 5450 5589 5447 5446 5731 5453 5451 5448 5447 5590 5732 5596 5453 5449 5448 5592 5733 5597 5596 5595 5449 5591 5734 5598 5597 5452 5595 5450 5735 5599 5598 5305 5452 5451 5736 5602 5737 5306 5305 5453 5600 5601 5458 5308 5306 5596 5601 5459 5603 5597 5455 5308 5738 5460 5459 5598 5456 5455 5739 5462 5460 5599 5457 5456 5740 5604 5462 5458 5457 5600 5741 5742 5743 5603 5458 5601 5605 5466 5606 5459 5461 5603 5742 5467 5466 5460 5463 5461 5744 5607 5467 5462 5464 5463 5607 5609 5470 5604 5465 5464 5609 5608 5471 5605 5606 5465 5745 5746 5747 5466 5468 5606 5611 5612 5320 5468 5467 5469 5746 5613 5612 5607 5470 5469 5613 5614 5323 5470 5609 5471 5748 5615 5614 5471 5608 5472 5615 5616 5475 5472 5611 5320 5749 5750 5751 5320 5612 5321 5617 5752 5618 5321 5613 5323 5752 5619 5330 5324 5323 5614 5753 5754 5755 5324 5615 5475 5620 5756 5621 5475 5616 5476 5756 5757 5622 5618 5476 5617 5757 5758 5335 5330 5618 5752 5758 5759 5333 5330 5619 5328 5759 5760 5626 5621 5328 5620 5760 5761 5627 5622 5621 5756 5761 5762 5628 5335 5622 5757 5762 5763 5629 5333 5335 5758 5763 5764 5630 5759 5626 5333 5764 5765 5631 5760 5627 5626 5765 5766 5632 5761 5628 5627 5766 5767 5633 5762 5629 5628 5767 5768 5634 5763 5630 5629 5768 5769 5635 5764 5631 5630 5769 5770 5636 5765 5632 5631 5770 5771 5637 5766 5633 5632 5771 5772 5638 5767 5634 5633 5772 5773 5639 5768 5635 5634 5773 5774 5640 5769 5636 5635 5774 5495 5641 5637 5636 5770 5495 5497 5642 5638 5637 5771 5497 5775 5643 5639 5638 5772 5775 5500 5644 5640 5639 5773 5776 5777 5778 5640 5774 5641 5501 5779 5645 5642 5641 5495 5779 5504 5646 5643 5642 5497 5780 5505 5504 5643 5775 5644 5505 5647 5358 5502 5644 5500 5781 5648 5647 5502 5501 5645 5648 5649 5361 5645 5779 5646 5782 5650 5649 5646 5504 5506 5650 5510 5651 5506 5505 5358 5783 5511 5510 5358 5647 5359 5784 5785 5786 5648 5361 5359 5652 5514 5653 5361 5649 5362 5785 5515 5514 5650 5651 5362 5787 5654 5515 5510 5512 5651 5654 5655 5518 5511 5513 5512 5655 5519 5657 5652 5653 5513 5788 5520 5519 5514 5516 5653 5789 5658 5520 5515 5517 5516 5790 5659 5658 5518 5517 5654 5791 5792 5793 5657 5518 5655 5794 5663 5792 5370 5657 5519 5661 5662 5525 5371 5370 5520 5662 5526 5664 5658 5522 5371 5795 5527 5526 5659 5523 5522 5796 5529 5527 5660 5524 5523 5797 5665 5529 5525 5524 5661 5798 5666 5665 5664 5525 5662 5799 5667 5666 5528 5664 5526 5800 5668 5667 5378 5528 5527 5801 5802 5803 5379 5378 5529 5804 5672 5802 5381 5379 5665 5670 5671 5535 5531 5381 5666 5671 5536 5673 5667 5532 5531 5805 5537 5536 5668 5533 5532 5806 5674 5537 5669 5534 5533 5807 5678 5808 5535 5534 5670 5675 5677 5540 5673 5535 5671 5677 5676 5391 5536 5387 5673 5809 5679 5676 5537 5388 5387 5810 5811 5812 5674 5539 5388 5680 5681 5395 5675 5540 5539 5811 5682 5681 5677 5391 5540 5682 5684 5544 5676 5392 5391 5684 5683 5545 5392 5679 5542 5683 5687 5546 5680 5395 5542 5687 5686 5547 5395 5681 5396 5686 5690 5548 5682 5544 5396 5690 5689 5552 5544 5684 5545 5689 168 5403 5545 5683 5546 5813 5814 5815 5546 5687 5547 5692 5816 174 5547 5686 5548 5816 180 175 5690 5552 5548 5556 182 5555 5550 5693 5555 175 5408 170 5403 168 5404 5551 5694 5693 5404 5692 174 5694 5817 5695 174 5816 175 173 5550 177 182 5556 180 5696 5697 5818 5818 5698 5561 5694 5695 5558 5551 5693 5550 5697 5819 5818 5551 5817 5694 5699 5701 5562 5695 5820 5560 5821 5822 5699 5823 5700 5824 5414 5561 5412 5696 5818 5561 4984 5700 5823 5564 5701 5700 5563 5562 5701 5701 5824 5700 4987 5700 4984 4983 5272 5565 5825 5271 5273 5417 5271 5825 5565 5705 5566 5271 5826 5705 5827 5423 5276 5826 5827 5275 5828 5829 5830 5276 5275 5827 5831 5277 5709 5276 5423 5425 711 5277 5832 5709 5425 5424 718 5712 716 5709 5424 5831 5713 710 541 5277 5831 5832 5428 5713 540 711 5832 712 5429 5428 5833 709 712 719 5717 5429 5716 541 710 719 5572 5717 5715 540 5713 541 5834 5835 5573 5428 540 5833 5575 5571 5835 5716 5429 5833 5836 5837 5576 5717 5716 5715 5577 5574 5837 5715 5573 5572 5578 5577 5720 5571 5573 5835 5838 5839 5840 5835 5576 5575 5581 5579 5841 5574 5576 5837 5839 5721 5582 5577 5837 5720 5842 5722 5843 5720 5719 5578 5584 5583 5844 5719 5841 5579 5585 5584 5723 5841 5582 5581 5845 5724 5586 5582 5721 5580 5846 5725 5724 5721 5844 5583 5847 5726 5848 5844 5723 5584 5589 5588 5849 5586 5585 5723 5590 5589 5728 5724 5443 5586 5592 5590 5727 5724 5725 5444 5850 5594 5593 5725 5849 5588 5851 5730 5594 5849 5728 5589 5852 5731 5730 5728 5727 5590 5853 5732 5731 5593 5592 5727 5854 5733 5732 5594 5591 5593 5855 5856 5857 5730 5450 5594 5858 5859 5856 5731 5451 5730 5860 5736 5859 5732 5453 5731 5600 5599 5861 5733 5596 5732 5601 5600 5737 5733 5734 5597 5862 5738 5602 5734 5735 5598 5863 5739 5738 5735 5861 5599 5864 5740 5739 5861 5737 5600 5865 5741 5866 5602 5601 5737 5605 5604 5867 5738 5459 5602 5466 5605 5743 5738 5739 5460 5868 5744 5742 5739 5740 5462 5869 5870 5871 5740 5867 5604 5609 5607 5872 5605 5867 5743 5870 5873 5610 5743 5742 5466 5611 5608 5873 5742 5744 5467 5612 5611 5747 5607 5744 5872 5874 5875 5876 5872 5610 5609 5614 5613 5877 5608 5610 5873 5878 5879 5880 5611 5873 5747 5616 5615 5881 5612 5747 5746 5617 5616 5882 5613 5746 5877 5752 5617 5750 5614 5877 5748 5619 5752 5749 5881 5615 5748 5620 5619 5883 5616 5881 5882 5756 5620 5884 5750 5617 5882 5757 5756 5885 5749 5752 5750 5758 5757 5886 5883 5619 5749 5759 5758 5887 5883 5884 5620 5760 5759 5888 5885 5756 5884 5761 5760 5889 5886 5757 5885 5762 5761 5623 5887 5758 5886 5763 5762 5625 5888 5759 5887 5764 5763 5890 5888 5889 5760 5765 5764 5891 5889 5623 5761 5766 5765 5892 5623 5625 5762 5767 5766 5893 5625 5890 5763 5768 5767 5894 5890 5891 5764 5769 5768 5895 5891 5892 5765 5770 5769 5896 5892 5893 5766 5771 5770 5897 5893 5894 5767 5772 5771 5898 5894 5895 5768 5773 5772 5899 5895 5896 5769 5774 5773 5900 5896 5897 5770 5495 5774 5901 5897 5898 5771 5902 5903 5904 5899 5772 5898 5775 5497 5905 5900 5773 5899 5500 5775 5906 5901 5774 5900 5501 5500 5907 5495 5901 5496 5779 5501 5778 5905 5497 5496 5504 5779 5777 5906 5775 5905 5908 5909 5910 5500 5906 5907 5647 5505 5911 5778 5501 5907 5912 5913 5914 5779 5778 5777 5649 5648 5915 5504 5777 5780 5916 5917 5918 5505 5780 5911 5510 5650 5919 5647 5911 5781 5917 5920 5783 5648 5781 5915 5652 5511 5920 5915 5782 5649 5514 5652 5786 5650 5782 5919 5921 5787 5785 5919 5783 5510 5922 5923 5924 5783 5920 5511 5655 5654 5925 5652 5920 5786 5923 5788 5656 5786 5785 5514 5926 5789 5788 5785 5787 5515 5927 5790 5789 5787 5925 5654 5928 5791 5929 5656 5655 5925 5660 5659 5930 5788 5519 5656 5661 5660 5793 5789 5520 5788 5662 5661 5792 5789 5790 5658 5931 5795 5663 5790 5930 5659 5932 5796 5795 5930 5793 5660 5933 5797 5796 5793 5792 5661 5934 5798 5797 5663 5662 5792 5935 5799 5798 5795 5526 5663 5936 5937 5938 5796 5527 5795 5939 5801 5937 5797 5529 5796 5669 5668 5940 5798 5665 5797 5670 5669 5803 5799 5666 5798 5671 5670 5802 5799 5800 5667 5941 5805 5672 5800 5940 5668 5942 5806 5805 5940 5803 5669 5943 5807 5944 5803 5802 5670 5675 5674 5945 5672 5671 5802 5677 5675 5808 5672 5805 5536 5946 5809 5678 5805 5806 5537 5947 5810 5948 5806 5945 5674 5680 5679 5949 5945 5808 5675 5681 5680 5812 5808 5678 5677 5950 5951 5952 5678 5809 5676 5684 5682 5953 5679 5809 5949 5951 5954 5685 5680 5949 5812 5687 5683 5954 5681 5812 5811 5955 5956 5688 5682 5811 5953 5690 5686 5956 5684 5953 5685 5957 5958 5959 5683 5685 5954 168 5689 169 5687 5954 5688 5692 168 167 5686 5688 5956 5816 5692 5815 5690 5956 5691 180 5816 5814 169 5689 5691 5960 171 176 5817 5551 172 180 5556 175 167 5815 5692 5820 5817 5961 5815 5814 5816 173 176 171 5814 181 180 5697 5962 5819 177 182 181 5818 5819 5963 5820 5697 5560 5817 5820 5695 173 172 5551 5821 5698 5963 172 5961 5817 5964 5963 5819 5697 5820 5962 5699 5822 5824 5822 5965 5966 5561 5698 5562 5698 5818 5963 5273 5823 5967 4982 4984 5823 5701 5699 5824 5823 5824 5968 5273 4982 5823 5272 5271 5705 5418 5417 5825 5416 5969 5417 5705 5826 5275 5417 5970 5826 5971 5972 5423 5971 5827 5970 5972 5973 5424 5423 5827 5971 5710 5832 5831 5424 5423 5972 712 5832 5712 5424 5973 5831 719 763 541 5710 5831 5973 5974 5975 5976 5710 5712 5832 540 5977 5833 712 5712 718 5833 5978 5716 763 719 718 5979 5980 5714 539 541 763 5715 5980 5573 5977 540 539 5981 5982 5983 5833 5977 5978 5835 5984 5576 5714 5716 5978 5985 5986 5987 5715 5714 5980 5837 5988 5720 5573 5980 5834 5985 5989 5718 5835 5834 5984 5719 5989 5841 5984 5836 5576 5841 5840 5582 5837 5836 5988 5990 5839 5991 5720 5988 5718 5721 5990 5844 5718 5989 5719 5844 5843 5723 5841 5989 5840 5992 5845 5722 5840 5839 5582 5846 5845 5993 5839 5990 5721 5847 5994 5995 5990 5843 5844 5725 5996 5849 5843 5722 5723 5849 5848 5728 5722 5845 5586 5997 5729 5726 5845 5846 5724 5998 5850 5729 5846 5996 5725 5851 5850 5999 5996 5848 5849 5852 5851 6000 5848 5726 5728 5853 5852 6001 5726 5729 5727 6002 6003 6004 5850 5593 5729 5855 6002 6005 5851 5594 5850 5733 6006 5734 5852 5730 5851 5734 5857 5735 5853 5731 5852 5735 5856 5861 5854 5732 5853 5861 5859 5737 5854 6006 5733 6007 5862 5736 6006 5857 5734 5863 5862 6008 5857 5856 5735 5864 5863 6009 5856 5859 5861 5865 6010 6011 5859 5736 5737 5740 6012 5867 5862 5602 5736 5867 5866 5743 5862 5863 5738 6013 5868 5741 5863 5864 5739 5869 6014 6015 5864 6012 5740 5744 6016 5872 6012 5866 5867 5872 5871 5610 5743 5866 5741 6017 6018 6019 5741 5868 5742 5873 6020 5747 5744 5868 6016 6017 6021 5745 5872 6016 5871 5746 6021 5877 5871 5870 5610 5877 5876 5748 5873 5870 6020 5748 5875 5881 5747 6020 5745 5881 5880 5882 5746 5745 6021 5882 5879 5750 5876 5877 6021 6022 6023 6024 5748 5876 5875 5749 6025 5883 5880 5881 5875 5883 6026 5884 5879 5882 5880 5885 5884 6027 5751 5750 5879 5885 5754 5886 6025 5749 5751 5886 5753 5887 6026 5883 6025 5887 6028 5888 6026 6027 5884 5888 6029 5889 6027 5754 5885 5623 5889 6030 5753 5886 5754 6031 6032 6033 6028 5887 5753 5625 6034 5890 6029 5888 6028 5890 6033 5891 6029 6030 5889 5891 6032 5892 6030 5624 5623 5892 6035 5893 5624 6034 5625 5893 6036 5894 6034 6033 5890 5894 6037 5895 6033 6032 5891 5895 6038 5896 6032 6035 5892 5896 6039 5897 6035 6036 5893 5897 6040 5898 6036 6037 5894 5898 6041 5899 6037 6038 5895 5899 6042 5900 6038 6039 5896 5900 6043 5901 6039 6040 5897 5901 6044 5496 6040 6041 5898 5496 6045 5905 6042 5899 6041 5905 5904 5906 6043 5900 6042 5906 5903 5907 6044 5901 6043 5907 6046 5778 6044 6045 5496 6047 6048 6049 5904 5905 6045 5777 6050 5780 5903 5906 5904 5780 6051 5911 5907 5903 6046 5911 5910 5781 5776 5778 6046 5781 5909 5915 5777 5776 6050 5915 5914 5782 5780 6050 6051 5782 5913 5919 5911 6051 5910 5919 5918 5783 5781 5910 5909 6052 6053 6054 5915 5909 5914 5920 6055 5786 5782 5914 5913 6052 5921 5784 5919 5913 5918 5922 6056 6057 5918 5917 5783 5787 6058 5925 5917 6055 5920 5925 5924 5656 5786 6055 5784 5926 5923 6059 5784 5921 5785 6060 6061 6062 5921 6058 5787 5928 6060 6063 6058 5924 5925 5790 6064 5930 5924 5923 5656 5930 5929 5793 5923 5926 5788 6065 5794 5791 5926 5927 5789 6066 5931 5794 5927 6064 5790 5932 5931 6067 6064 5929 5930 5933 5932 6068 5929 5791 5793 6069 6070 6071 5791 5794 5792 6072 6069 6073 5931 5663 5794 5936 6072 6074 5932 5795 5931 5799 6075 5800 5933 5796 5932 5800 5938 5940 5934 5797 5933 5940 5937 5803 5934 5935 5798 6076 5804 5801 5935 6075 5799 6077 5941 5804 6075 5938 5800 5942 5941 6078 5938 5937 5940 5943 6079 6080 5937 5801 5803 5806 6081 5945 5801 5804 5802 5945 5944 5808 5804 5941 5672 6082 5946 5807 5941 5942 5805 6083 5946 6084 5942 6081 5806 5809 6083 5949 6081 5944 5945 5949 5948 5812 5808 5944 5807 6085 6086 5810 5807 5946 5678 5811 6086 5953 5946 6083 5809 5953 5952 5685 5949 6083 5948 6087 6088 6089 5812 5948 5810 5954 6090 5688 5811 5810 6086 6091 6092 6093 5953 6086 5952 5956 6094 5691 5685 5952 5951 5691 6095 169 5954 5951 6090 169 5959 167 5688 6090 5955 167 5958 5815 6094 5956 5955 6096 6097 6098 5691 6094 6095 5814 6099 181 5959 169 6095 181 6100 177 5959 5958 167 177 5550 182 5813 5815 5958 172 179 5961 6099 5814 5813 5961 6101 5962 6100 181 6099 178 171 5960 177 6100 176 5964 5819 6102 6103 5963 5964 5961 5962 5820 171 179 172 5965 5821 6103 179 6101 5961 6103 5964 6104 5962 6102 5819 5822 5966 5968 6105 6106 5967 5698 5821 5699 5821 5963 6103 5825 5967 6106 5823 5968 5967 5824 5822 5968 5968 6105 5967 5273 5967 5825 5271 5417 5826 6107 5969 5416 6107 5706 5969 5826 5970 5827 5969 6108 5970 5972 6109 6110 6109 5971 6108 6110 6111 5973 6109 5972 5971 6112 6113 6114 5973 5972 6110 6115 727 720 6111 5710 5973 763 6116 539 5711 5710 6111 5977 539 6117 716 5712 5711 5977 5976 5978 715 718 716 5978 5975 5714 6116 763 715 6118 6119 6120 6117 539 6116 5980 6121 5834 5976 5977 6117 5834 6122 5984 5978 5976 5975 5984 5982 5836 5979 5714 5975 5836 5981 5988 5980 5979 6121 5988 5986 5718 6122 5834 6121 6123 6124 6125 5984 6122 5982 5989 6126 5840 5836 5982 5981 6124 5991 5838 5988 5981 5986 6127 6128 6129 5718 5986 5985 5990 6130 5843 5989 5985 6126 6127 5992 5842 5840 6126 5838 6131 5993 5992 5838 5991 5839 5995 6132 6133 5991 6130 5990 5846 6134 5996 6130 5842 5843 5996 5994 5848 5722 5842 5992 6135 5997 5847 5992 5993 5845 6136 5998 5997 5993 6134 5846 6137 5999 5998 6134 5994 5996 6138 6139 6140 5994 5847 5848 6141 6138 6142 5847 5997 5726 6004 6141 6143 5997 5998 5729 5853 6144 5854 5998 5999 5850 5854 6003 6006 6000 5851 5999 6006 6002 5857 6000 6001 5852 6145 5858 5855 6001 6144 5853 6146 5860 5858 6144 6003 5854 6147 6007 5860 6003 6002 6006 6148 6008 6007 6002 5855 5857 6149 6150 6151 5855 5858 5856 6011 6149 6152 5858 5860 5859 5864 6153 6012 5860 6007 5736 6012 6010 5866 5862 6007 6008 6154 6013 5865 6008 6009 5863 6155 6156 6013 6009 6153 5864 5868 6156 6016 6153 6010 6012 6016 6014 5871 5866 6010 5865 6157 6158 5869 5741 5865 6013 5870 6158 6020 6013 6156 5868 6020 6018 5745 6016 6156 6014 6159 6160 6161 5871 6014 5869 6021 6162 5876 5870 5869 6158 6160 6163 5874 6020 6158 6018 5875 6163 5880 6017 5745 6018 6164 6165 6166 6021 6017 6162 5879 6167 5751 5874 5876 6162 6025 5751 6168 5875 5874 6163 6025 6024 6026 5878 5880 6163 6026 6023 6027 6167 5879 5878 5754 6027 6169 6167 6168 5751 6170 6171 6172 6024 6025 6168 5753 6173 6028 6023 6026 6024 6028 6174 6029 6023 6169 6027 6029 6175 6030 6169 5755 5754 5624 6030 6176 5755 6173 5753 6034 5624 6177 6173 6174 6028 6033 6034 6178 6175 6029 6174 6179 6035 6032 6175 6176 6030 6180 6036 6035 6176 6177 5624 6181 6037 6036 6177 6178 6034 6182 6038 6037 6178 6031 6033 6183 6039 6038 6031 6179 6032 6184 6040 6039 6179 6180 6035 6185 6186 6187 6180 6181 6036 6040 6188 6041 6181 6182 6037 6041 6187 6042 6182 6183 6038 6042 6186 6043 6183 6184 6039 6043 6189 6044 6184 6188 6040 6044 6190 6045 6188 6187 6041 5904 6045 6191 6187 6186 6042 6192 6193 6194 6189 6043 6186 5903 6195 6046 6190 6044 6189 6046 6196 5776 6190 6191 6045 6050 5776 6197 5902 5904 6191 6050 6049 6051 6195 5903 5902 6051 6048 5910 6196 6046 6195 6198 6199 5908 6197 5776 6196 5909 6199 5914 6049 6050 6197 6200 6201 5912 6051 6049 6048 5913 6201 5918 5908 5910 6048 6202 6203 5916 5909 5908 6199 5917 6203 6055 5914 6199 5912 6055 6053 5784 5913 5912 6201 6204 6205 6052 5918 6201 5916 5921 6205 6058 5916 6203 5917 6058 6056 5924 6055 6203 6053 6206 6059 5922 5784 6053 6052 6207 6062 6208 6052 6205 5921 5926 6209 5927 6205 6056 6058 5927 6061 6064 6056 5922 5924 6064 6060 5929 5923 5922 6059 6210 6065 5928 6059 6209 5926 6211 6066 6065 6209 6061 5927 6212 6067 6066 6061 6060 6064 6213 6214 6215 6060 5928 5929 6071 6213 6216 5928 6065 5791 5933 6217 5934 6065 6066 5794 5934 6070 5935 6067 5931 6066 5935 6069 6075 6068 5932 6067 6075 6072 5938 6068 6217 5933 6218 5939 5936 6217 6070 5934 6219 6076 5939 6070 6069 5935 6220 6077 6076 6069 6072 6075 6221 6078 6077 6072 5936 5938 6080 6222 6223 5936 5939 5937 5942 6224 6081 5939 6076 5801 6081 6079 5944 5804 6076 6077 6225 6082 5943 6077 6078 5941 6226 6084 6082 6078 6224 5942 6227 6228 6229 6224 6079 6081 6083 6230 5948 5944 6079 5943 6227 6085 5947 5807 5943 6082 6231 6232 6233 6082 6084 5946 6086 6234 5952 6083 6084 6230 6232 6235 5950 5948 6230 5947 5951 6235 6090 5810 5947 6085 6090 6088 5955 6086 6085 6234 5955 6087 6094 5952 6234 5950 6094 6092 6095 5951 5950 6235 6095 6091 5959 6088 6090 6235 6236 6237 5957 5955 6088 6087 5958 6237 5813 6092 6094 6087 6099 5813 6238 6095 6092 6091 6099 6098 6100 5957 5959 6091 6100 6097 176 6237 5958 5957 185 6239 6240 5813 6237 6238 179 187 6101 6099 6238 6098 6101 6241 6102 6100 6098 6097 178 6242 186 176 6097 5960 6104 5964 6243 6103 6104 6244 6101 6102 5962 178 187 179 6245 5965 6244 187 6241 6101 6246 6105 5966 6102 6243 5964 6246 6247 6248 6249 6106 6250 5821 5965 5822 5965 6103 6244 6246 5966 6245 5416 5418 6106 5968 5966 6105 6105 6250 6106 5825 6106 5418 5417 5969 5970 5707 5706 6107 6251 6252 6253 5970 6108 5971 5706 6254 6108 6110 6255 5830 6254 6255 6109 5830 6256 6111 6110 6109 6255 6257 716 5711 6110 5830 6111 715 721 6116 5711 6111 6256 6116 6258 6117 6257 5711 6256 5976 6117 6259 717 716 6257 6260 6261 6262 721 715 717 5975 6263 5979 6258 6116 721 6121 5979 6264 6259 6117 6258 6121 6120 6122 5974 5976 6259 5982 6122 6119 6263 5975 5974 6265 6266 5983 6264 5979 6263 5981 6266 5986 6120 6121 6264 6267 6268 5987 6119 6122 6120 6126 5985 6268 5982 6119 5983 6126 6125 5838 5981 5983 6266 6269 6270 6129 5986 6266 5987 5991 6271 6130 5985 5987 6268 6130 6128 5842 6126 6268 6125 6272 6131 6127 5838 6125 6124 6273 6133 6274 5991 6124 6271 5993 6275 6134 6271 6128 6130 6134 6132 5994 5842 6128 6127 6276 6135 5995 5992 6127 6131 6277 6136 6135 6131 6275 5993 6278 6137 6136 6275 6132 6134 6279 6280 6140 6132 5995 5994 6000 5999 6281 5995 6135 5847 6000 6139 6001 6135 6136 5997 6001 6138 6144 6136 6137 5998 6144 6141 6003 5999 6137 6281 6282 6005 6004 6281 6139 6000 6283 6145 6005 6139 6138 6001 6284 6146 6145 6138 6141 6144 6285 6147 6146 6141 6004 6003 6286 6148 6147 6004 6005 6002 6287 6288 6151 6005 6145 5855 6009 6008 6289 6145 6146 5858 6009 6150 6153 6146 6147 5860 6153 6149 6010 6007 6147 6148 6290 6154 6011 6008 6148 6289 6291 6155 6154 6289 6150 6009 6292 6293 6294 6150 6149 6153 6156 6295 6014 6010 6149 6011 6293 6157 6015 5865 6011 6154 6296 6297 6298 6013 6154 6155 6158 6299 6018 6156 6155 6295 6297 6300 6019 6014 6295 6015 6162 6017 6300 5869 6015 6157 6162 6161 5874 6158 6157 6299 6301 6302 6303 6018 6299 6019 6163 6304 5878 6300 6017 6019 6167 5878 6305 6162 6300 6161 6167 6166 6168 6160 5874 6161 6024 6168 6165 6304 6163 6160 6306 6307 6308 6305 5878 6304 6023 6309 6169 6166 6167 6305 5755 6169 6310 6166 6165 6168 6173 5755 6311 6022 6024 6165 6173 6172 6174 6309 6023 6022 6174 6171 6175 6309 6310 6169 6175 6312 6176 6310 6311 5755 6177 6176 6313 6311 6172 6173 6178 6177 6314 6172 6171 6174 6031 6178 6315 6171 6312 6175 6179 6031 6316 6176 6312 6313 6180 6179 6317 6177 6313 6314 6181 6180 6318 6178 6314 6315 6182 6181 6319 6031 6315 6316 6183 6182 6320 6179 6316 6317 6184 6183 6321 6180 6317 6318 6188 6184 6322 6181 6318 6319 6187 6188 6323 6319 6320 6182 6324 6325 6326 6320 6321 6183 6186 6327 6189 6321 6322 6184 6189 6328 6190 6322 6323 6188 6190 6329 6191 6323 6185 6187 5902 6191 6330 6185 6327 6186 6195 5902 6331 6328 6189 6327 6195 6194 6196 6329 6190 6328 6196 6193 6197 6329 6330 6191 6049 6197 6332 6330 6331 5902 6333 6334 6047 6194 6195 6331 6048 6334 5908 6193 6196 6194 6335 6336 6337 6332 6197 6193 6199 6338 5912 6047 6049 6332 6339 6340 6341 6048 6047 6334 6201 6342 5916 6198 5908 6334 6343 6344 6345 6199 6198 6338 6203 6346 6053 6200 5912 6338 6344 6204 6054 6201 6200 6342 6347 6348 6349 5916 6342 6202 6205 6350 6056 6203 6202 6346 6348 6206 6057 6053 6346 6054 6351 6352 6207 6052 6054 6204 6209 6059 6353 6204 6350 6205 6209 6208 6061 6056 6350 6057 6354 6063 6062 5922 6057 6206 6355 6210 6063 6059 6206 6353 6356 6211 6210 6353 6208 6209 6357 6358 6359 6208 6062 6061 6360 6215 6359 6062 6063 6060 6067 6361 6068 6063 6210 5928 6068 6214 6217 6210 6211 6065 6217 6213 6070 6066 6211 6212 6362 6073 6071 6212 6361 6067 6363 6074 6073 6361 6214 6068 6364 6218 6074 6214 6213 6217 6365 6219 6218 6213 6071 6070 6366 6220 6219 6071 6073 6069 6367 6368 6369 6073 6074 6072 6370 6223 6369 6074 6218 5936 6078 6371 6224 6218 6219 5939 6224 6222 6079 6076 6219 6220 6372 6225 6080 6077 6220 6221 6373 6226 6225 6221 6371 6078 6374 6375 6229 6371 6222 6224 6084 6376 6230 6222 6080 6079 6230 6228 5947 5943 6080 6225 6377 6378 6227 6082 6225 6226 6234 6085 6378 6226 6376 6084 6234 6233 5950 6230 6376 6228 6379 6380 6381 5947 6228 6227 6235 6382 6088 6378 6085 6227 6380 6383 6089 6234 6378 6233 6087 6383 6092 6232 5950 6233 6384 6385 6093 6235 6232 6382 6091 6385 5957 6089 6088 6382 6386 6387 6388 6383 6087 6089 6237 6389 6238 6093 6092 6383 6098 6238 6390 6385 6091 6093 6391 6392 6393 6236 5957 6385 6097 6394 5960 6389 6237 6236 5960 6242 178 6390 6238 6389 6240 6241 187 6096 6098 6390 6241 6239 6243 6097 6096 6394 6395 186 6392 6394 6242 5960 6396 6104 6397 6398 6247 6245 6241 6243 6102 6240 187 186 6396 190 6398 6240 6239 6241 6248 6250 6246 6243 6397 6104 6104 6396 6244 6248 6399 6400 5965 6245 5966 6245 6244 6398 6107 6249 6401 6249 5416 6106 6105 6246 6250 6249 6250 6402 6107 5416 6249 5969 5706 6108 5704 5708 5707 5703 5708 5704 6108 6254 6109 6254 5708 6403 6252 6404 6405 6403 5828 6255 5829 6112 6256 5830 6255 5828 6115 717 6257 5829 6256 5830 721 762 6258 6256 6112 6257 6258 6406 6259 6115 6257 6112 5974 6259 6407 6115 720 717 6263 5974 6408 762 721 720 6263 6262 6264 6406 6258 762 6120 6264 6261 6406 6407 6259 6409 6410 6411 6408 5974 6407 5983 6119 6412 6262 6263 6408 6413 6414 6415 6261 6264 6262 6266 6416 5987 6118 6120 6261 6417 6418 6419 6412 6119 6118 6125 6268 6420 6265 5983 6412 6419 6421 6123 6416 6266 6265 6271 6124 6421 5987 6416 6267 6128 6271 6269 6420 6268 6267 6422 6272 6129 6125 6420 6123 6423 6424 6273 6124 6123 6421 6275 6131 6425 6271 6421 6269 6275 6274 6132 6128 6269 6129 6426 6276 6133 6127 6129 6272 6427 6277 6276 6131 6272 6425 6428 6429 6430 6425 6274 6275 6430 6431 6280 6274 6133 6132 6281 6137 6432 6133 6276 5995 6139 6281 6279 6135 6276 6277 6433 6142 6140 6136 6277 6278 6434 6143 6142 6137 6278 6432 6435 6282 6143 6281 6432 6279 6436 6283 6282 6279 6140 6139 6437 6284 6283 6140 6142 6138 6438 6285 6284 6142 6143 6141 6439 6440 6441 6143 6282 6004 6441 6442 6288 6282 6283 6005 6289 6148 6443 6283 6284 6145 6150 6289 6287 6146 6284 6285 6444 6152 6151 6147 6285 6286 6445 6290 6152 6148 6286 6443 6446 6291 6290 6289 6443 6287 6447 6448 6292 6287 6151 6150 6295 6155 6449 6151 6152 6149 6295 6294 6015 6011 6152 6290 6450 6451 6293 6154 6290 6291 6299 6157 6451 6155 6291 6449 6299 6298 6019 6295 6449 6294 6452 6453 6297 6015 6294 6293 6161 6300 6453 6451 6157 6293 6454 6455 6159 6299 6451 6298 6304 6160 6455 6019 6298 6297 6304 6303 6305 6453 6300 6297 6166 6305 6302 6159 6161 6453 6456 6457 6164 6455 6160 6159 6022 6165 6457 6303 6304 6455 6309 6022 6458 6302 6305 6303 6309 6308 6310 6164 6166 6302 6311 6310 6307 6164 6457 6165 6172 6311 6459 6457 6458 6022 6460 6461 6462 6308 6309 6458 6171 6463 6312 6308 6307 6310 6312 6464 6313 6307 6459 6311 6314 6313 6465 6459 6170 6172 6315 6314 6466 6170 6463 6171 6316 6315 6467 6463 6464 6312 6317 6316 6468 6313 6464 6465 6318 6317 6469 6314 6465 6466 6319 6318 6470 6315 6466 6467 6320 6319 6471 6316 6467 6468 6321 6320 6472 6317 6468 6469 6322 6321 6473 6318 6469 6470 6323 6322 6474 6319 6470 6471 6185 6323 6475 6320 6471 6472 6327 6185 6476 6321 6472 6473 6328 6327 6477 6473 6474 6322 6328 6478 6329 6474 6475 6323 6329 6479 6330 6475 6476 6185 6331 6330 6480 6476 6477 6327 6194 6331 6481 6477 6478 6328 6482 6483 6484 6479 6329 6478 6193 6485 6332 6479 6480 6330 6047 6332 6486 6480 6481 6331 6487 6488 6489 6192 6194 6481 6334 6490 6198 6485 6193 6192 6338 6198 6491 6486 6332 6485 6338 6337 6200 6333 6047 6486 6342 6200 6336 6334 6333 6490 6342 6341 6202 6491 6198 6490 6346 6202 6340 6338 6491 6337 6346 6345 6054 6336 6200 6337 6492 6493 6347 6342 6336 6341 6350 6204 6494 6202 6341 6340 6350 6349 6057 6346 6340 6345 6495 6496 6348 6054 6345 6344 6353 6206 6496 6204 6344 6494 6208 6353 6351 6350 6494 6349 6497 6354 6207 6057 6349 6348 6498 6355 6354 6206 6348 6496 6499 6500 6501 6353 6496 6351 6501 6502 6358 6351 6207 6208 6212 6211 6503 6207 6354 6062 6361 6212 6357 6354 6355 6063 6361 6359 6214 6210 6355 6356 6504 6216 6215 6211 6356 6503 6505 6362 6216 6212 6503 6357 6506 6363 6362 6357 6359 6361 6507 6364 6363 6359 6215 6214 6508 6365 6364 6215 6216 6213 6509 6510 6511 6216 6362 6071 6511 6512 6368 6362 6363 6073 6221 6220 6513 6363 6364 6074 6371 6221 6367 6364 6365 6218 6371 6369 6222 6219 6365 6366 6514 6372 6223 6220 6366 6513 6515 6373 6372 6221 6513 6367 6516 6517 6375 6367 6369 6371 6376 6226 6518 6369 6223 6222 6376 6374 6228 6080 6223 6372 6519 6377 6229 6225 6372 6373 6520 6521 6522 6226 6373 6518 6233 6378 6523 6374 6376 6518 6522 6524 6231 6228 6374 6229 6382 6232 6524 6227 6229 6377 6382 6381 6089 6523 6378 6377 6525 6526 6527 6233 6523 6231 6093 6383 6528 6524 6232 6231 6529 6530 6531 6382 6524 6381 6385 6532 6236 6380 6089 6381 6389 6236 6533 6528 6383 6380 6389 6388 6390 6384 6093 6528 6096 6390 6387 6532 6385 6384 6394 6096 6534 6533 6236 6532 6394 6393 6242 6388 6389 6533 6242 6392 186 6388 6387 6390 6240 186 6395 6096 6387 6534 184 6397 6239 6394 6534 6393 6396 217 190 6242 6393 6392 6398 190 6535 6535 6399 6247 6239 6397 6243 185 6240 6395 6396 6398 6244 185 184 6239 192 6535 190 6396 6397 217 6248 6400 6402 6400 6536 6537 6245 6247 6246 6247 6398 6535 5707 6401 6538 6249 6402 6401 6250 6248 6402 6401 6402 6539 6107 6401 5707 5708 6254 5706 6540 5703 5702 6540 6541 5703 6254 6403 6255 5703 6542 6403 6543 6113 5829 6542 6543 5828 735 6544 6545 5829 5828 6543 6546 729 733 5829 6113 6112 6406 762 6547 6114 6115 6112 6406 723 6407 727 6115 6114 6408 6407 722 727 726 720 6262 6408 6548 726 6547 762 6549 6550 6260 723 6406 6547 6118 6261 6550 723 722 6407 6412 6118 6551 6548 6408 722 6265 6412 6409 6260 6262 6548 6416 6265 6411 6550 6261 6260 6267 6416 6413 6551 6118 6550 6420 6267 6415 6409 6412 6551 6123 6420 6417 6411 6265 6409 6552 6553 6554 6413 6416 6411 6269 6421 6555 6415 6267 6413 6270 6554 6422 6417 6420 6415 6556 6557 6424 6123 6417 6419 6425 6272 6558 6421 6419 6555 6274 6425 6423 6270 6269 6555 6559 6426 6273 6129 6270 6422 6560 6427 6426 6272 6422 6558 6561 6562 6429 6425 6558 6423 6278 6277 6563 6423 6273 6274 6432 6278 6428 6273 6426 6133 6279 6432 6430 6276 6426 6427 6280 6564 6433 6277 6427 6563 6565 6434 6433 6278 6563 6428 6566 6435 6434 6432 6428 6430 6567 6436 6435 6279 6430 6280 6568 6569 6570 6280 6433 6140 6570 6571 6572 6433 6434 6142 6572 6573 6440 6434 6435 6143 6286 6285 6574 6435 6436 6282 6443 6286 6439 6436 6437 6283 6287 6443 6441 6284 6437 6438 6288 6575 6444 6285 6438 6574 6576 6445 6444 6286 6574 6439 6577 6446 6445 6443 6439 6441 6578 6579 6448 6287 6441 6288 6449 6291 6580 6288 6444 6151 6294 6449 6447 6152 6444 6445 6581 6450 6292 6290 6445 6446 6582 6583 6584 6291 6446 6580 6298 6451 6585 6447 6449 6580 6584 6452 6296 6294 6447 6292 6586 6587 6588 6293 6292 6450 6159 6453 6589 6585 6451 6450 6590 6591 6592 6298 6585 6296 6303 6455 6593 6452 6297 6296 6594 6595 6596 6589 6453 6452 6164 6302 6597 6454 6159 6589 6598 6599 6600 6593 6455 6454 6458 6457 6601 6301 6303 6593 6308 6458 6602 6301 6597 6302 6603 6604 6605 6456 6164 6597 6459 6307 6606 6456 6601 6457 6170 6459 6607 6601 6602 6458 6463 6170 6608 6306 6308 6602 6463 6609 6464 6306 6606 6307 6464 6610 6465 6606 6607 6459 6466 6465 6611 6607 6608 6170 6467 6466 6612 6608 6609 6463 6468 6467 6613 6609 6610 6464 6469 6468 6614 6465 6610 6611 6470 6469 6615 6466 6611 6612 6471 6470 6616 6467 6612 6613 6472 6471 6617 6468 6613 6614 6473 6472 6618 6469 6614 6615 6474 6473 6619 6470 6615 6616 6475 6474 6620 6471 6616 6617 6476 6475 6621 6472 6617 6618 6477 6476 6622 6473 6618 6619 6478 6477 6623 6474 6619 6620 6479 6478 6624 6620 6621 6475 6479 6324 6480 6621 6622 6476 6481 6480 6326 6622 6623 6477 6192 6481 6625 6623 6624 6478 6485 6192 6626 6324 6479 6624 6485 6484 6486 6324 6326 6480 6333 6486 6483 6326 6625 6481 6490 6333 6627 6626 6192 6625 6490 6489 6491 6484 6485 6626 6337 6491 6488 6484 6483 6486 6628 6629 6630 6627 6333 6483 6341 6336 6631 6489 6490 6627 6630 6632 6339 6488 6491 6489 6345 6340 6632 6335 6337 6488 6633 6634 6343 6631 6336 6335 6494 6344 6634 6341 6631 6339 6349 6494 6492 6632 6340 6339 6635 6495 6347 6345 6632 6343 6636 6637 6638 6344 6343 6634 6351 6496 6639 6492 6494 6634 6352 6638 6497 6349 6492 6347 6640 6498 6497 6348 6347 6495 6641 6642 6500 6496 6495 6639 6356 6355 6643 6351 6639 6352 6503 6356 6499 6352 6497 6207 6357 6503 6501 6354 6497 6498 6358 6644 6360 6355 6498 6643 6360 6645 6504 6356 6643 6499 6646 6505 6504 6503 6499 6501 6647 6506 6505 6357 6501 6358 6648 6507 6506 6359 6358 6360 6649 6650 6651 6360 6504 6215 6651 6652 6510 6504 6505 6216 6366 6365 6653 6505 6506 6362 6513 6366 6509 6506 6507 6363 6367 6513 6511 6364 6507 6508 6368 6654 6370 6365 6508 6653 6370 6655 6514 6366 6653 6509 6656 6515 6514 6513 6509 6511 6657 6658 6517 6367 6511 6368 6518 6373 6659 6369 6368 6370 6374 6518 6516 6223 6370 6514 6375 6660 6519 6372 6514 6515 6661 6662 6519 6373 6515 6659 6523 6377 6662 6518 6659 6516 6231 6523 6520 6375 6374 6516 6663 6664 6522 6229 6375 6519 6381 6524 6664 6662 6377 6519 6665 6666 6379 6520 6523 6662 6528 6380 6666 6231 6520 6522 6384 6528 6525 6664 6524 6522 6532 6384 6527 6381 6664 6379 6532 6531 6533 6666 6380 6379 6388 6533 6530 6666 6525 6528 6667 6668 6669 6527 6384 6525 6534 6387 6670 6531 6532 6527 6393 6534 6671 6531 6530 6533 198 200 6672 6386 6388 6530 6392 6673 6395 6386 6670 6387 185 6395 6674 6670 6671 6534 6675 195 6676 6393 6671 6391 6677 6678 6674 6391 6673 6392 6395 6673 6674 6679 6535 192 184 217 6397 183 185 6674 6536 6399 6679 183 201 184 6679 192 6680 217 191 190 6400 6537 6539 6681 6538 6682 6247 6399 6248 6399 6535 6679 5704 6538 6681 6401 6539 6538 6402 6400 6539 6539 6682 6538 5707 6538 5704 5708 5703 6403 6683 6541 6540 6683 6684 6541 6403 6542 5828 6541 6685 6542 6113 6686 6687 6686 6543 6685 6687 6688 6114 6113 6543 6686 6547 726 728 6687 6114 6113 723 6547 6689 6688 727 6114 6690 6691 6692 6688 725 727 6548 722 6693 725 728 726 6260 6548 6694 728 6689 6547 6695 6696 6697 724 723 6689 6551 6550 6698 724 6693 722 6409 6551 6699 6693 6694 6548 6410 6700 6701 6549 6260 6694 6413 6411 6701 6549 6698 6550 6414 6702 6703 6699 6551 6698 6417 6415 6703 6699 6410 6409 6418 6704 6705 6701 6411 6410 6555 6419 6705 6414 6413 6701 6270 6555 6552 6703 6415 6414 6554 6706 6707 6418 6417 6703 6558 6422 6707 6419 6418 6705 6423 6558 6556 6552 6555 6705 6424 6708 6559 6554 6270 6552 6709 6560 6559 6422 6554 6707 6710 6711 6712 6558 6707 6556 6563 6427 6713 6423 6556 6424 6428 6563 6561 6273 6424 6559 6429 6714 6431 6426 6559 6560 6431 6715 6564 6427 6560 6713 6564 6716 6565 6563 6713 6561 6717 6566 6565 6428 6561 6429 6718 6719 6720 6430 6429 6431 6721 6722 6718 6280 6431 6564 6437 6436 6723 6564 6565 6433 6438 6437 6568 6565 6566 6434 6574 6438 6570 6566 6567 6435 6439 6574 6572 6436 6567 6723 6440 6724 6442 6437 6723 6568 6442 6725 6575 6438 6568 6570 6575 6726 6576 6574 6570 6572 6727 6728 6729 6439 6572 6440 6730 6731 6727 6441 6440 6442 6580 6446 6732 6288 6442 6575 6447 6580 6578 6444 6575 6576 6448 6733 6581 6445 6576 6577 6734 6735 6736 6446 6577 6732 6585 6450 6737 6580 6732 6578 6296 6585 6582 6448 6447 6578 6738 6739 6584 6292 6448 6581 6589 6452 6739 6450 6581 6737 6454 6589 6586 6582 6585 6737 6593 6454 6588 6296 6582 6584 6301 6593 6590 6739 6452 6584 6597 6301 6592 6586 6589 6739 6456 6597 6594 6588 6454 6586 6601 6456 6596 6590 6593 6588 6602 6601 6598 6592 6301 6590 6306 6602 6600 6592 6594 6597 6606 6306 6740 6596 6456 6594 6607 6606 6603 6596 6598 6601 6608 6607 6605 6598 6600 6602 6609 6608 6741 6600 6740 6306 6610 6609 6742 6740 6603 6606 6610 6743 6611 6603 6605 6607 6612 6611 6744 6605 6741 6608 6613 6612 6745 6741 6742 6609 6614 6613 6746 6742 6743 6610 6615 6614 6747 6611 6743 6744 6616 6615 6748 6612 6744 6745 6617 6616 6749 6613 6745 6746 6618 6617 6750 6614 6746 6747 6619 6618 6751 6615 6747 6748 6620 6619 6752 6616 6748 6749 6621 6620 6753 6617 6749 6750 6622 6621 6754 6618 6750 6751 6623 6622 6755 6619 6751 6752 6624 6623 6756 6620 6752 6753 6324 6624 6757 6621 6753 6754 6758 6759 6760 6754 6755 6622 6625 6326 6761 6755 6756 6623 6626 6625 6762 6756 6757 6624 6484 6626 6763 6757 6325 6324 6764 6765 6766 6325 6761 6326 6627 6483 6767 6761 6762 6625 6489 6627 6768 6762 6763 6626 6769 6770 6771 6482 6484 6763 6335 6488 6772 6482 6767 6483 6631 6335 6773 6768 6627 6767 6339 6631 6628 6487 6489 6768 6774 6775 6776 6772 6488 6487 6343 6632 6777 6773 6335 6772 6778 6779 6780 6628 6631 6773 6492 6634 6781 6630 6339 6628 6493 6782 6635 6777 6632 6630 6783 6784 6785 6343 6777 6633 6639 6495 6786 6634 6633 6781 6352 6639 6636 6493 6492 6781 6638 6787 6640 6347 6493 6635 6788 6789 6790 6495 6635 6786 6643 6498 6791 6639 6786 6636 6499 6643 6641 6638 6352 6636 6500 6792 6502 6497 6638 6640 6502 6793 6644 6498 6640 6791 6644 6794 6645 6643 6791 6641 6645 6795 6646 6499 6641 6500 6796 6797 6798 6501 6500 6502 6799 6800 6796 6358 6502 6644 6801 6802 6799 6360 6644 6645 6508 6507 6803 6645 6646 6504 6653 6508 6649 6646 6647 6505 6509 6653 6651 6506 6647 6648 6510 6804 6512 6507 6648 6803 6512 6805 6654 6508 6803 6649 6654 6806 6655 6653 6649 6651 6655 6807 6656 6509 6651 6510 6808 6809 6810 6511 6510 6512 6659 6515 6811 6368 6512 6654 6516 6659 6657 6655 6370 6654 6517 6812 6660 6514 6655 6656 6660 6813 6661 6515 6656 6811 6814 6815 6816 6659 6811 6657 6520 6662 6817 6517 6516 6657 6521 6818 6663 6660 6375 6517 6819 6820 6821 6519 6660 6661 6379 6664 6822 6817 6662 6661 6823 6824 6665 6521 6520 6817 6525 6666 6824 6663 6522 6521 6526 6825 6826 6822 6664 6663 6531 6527 6826 6665 6379 6822 6827 6828 6529 6824 6666 6665 6386 6530 6828 6824 6526 6525 6670 6386 6829 6826 6527 6526 6671 6670 6667 6529 6531 6826 6391 6671 6669 6529 6828 6530 6673 6391 6830 6829 6386 6828 6673 6677 6674 6829 6667 6670 183 6674 6678 6667 6669 6671 201 183 6831 6830 6391 6669 200 6678 6832 6677 6673 6830 6680 192 6833 6679 6680 6834 201 191 217 183 6678 6831 6835 6536 6834 6831 202 201 6834 6680 193 191 6833 192 6836 6837 6838 6839 6681 6840 6399 6536 6400 6536 6679 6834 6836 6537 6835 5702 5704 6681 6539 6537 6682 6681 6682 6840 6540 5702 6681 5703 6541 6542 6841 6684 6683 6841 6404 6684 6542 6685 6543 6684 6842 6685 6687 6843 6544 6842 6843 6686 6544 734 6688 6686 6843 6687 6689 728 6844 6687 6544 6688 724 6689 6845 6688 734 725 6693 724 6846 734 729 725 6694 6693 6691 729 6844 728 6549 6694 6847 6844 6845 6689 6698 6549 6848 6846 724 6845 6699 6698 6696 6846 6691 6693 6410 6699 6849 6691 6847 6694 6850 6851 6852 6848 6549 6847 6414 6701 6853 6848 6696 6698 6854 6855 6856 6849 6699 6696 6418 6703 6857 6849 6700 6410 6858 6859 6860 6853 6701 6700 6552 6705 6861 6853 6702 6414 6862 6553 6860 6857 6703 6702 6863 6864 6865 6704 6418 6857 6556 6707 6866 6861 6705 6704 6867 6557 6865 6553 6552 6861 6868 6869 6870 6706 6554 6553 6869 6871 6712 6707 6706 6866 6713 6560 6872 6556 6866 6557 6561 6713 6711 6708 6424 6557 6873 6562 6710 6709 6559 6708 6874 6714 6873 6560 6709 6872 6875 6876 6877 6713 6872 6711 6876 6878 6879 6561 6711 6562 6880 6720 6878 6429 6562 6714 6567 6566 6881 6431 6714 6715 6723 6567 6719 6564 6715 6716 6568 6723 6722 6565 6716 6717 6882 6569 6721 6566 6717 6881 6883 6571 6882 6567 6881 6719 6884 6573 6883 6723 6719 6722 6885 6724 6884 6568 6722 6569 6886 6887 6888 6570 6569 6571 6887 6889 6729 6572 6571 6573 6577 6576 6890 6440 6573 6724 6732 6577 6728 6442 6724 6725 6578 6732 6731 6726 6575 6725 6891 6579 6730 6576 6726 6890 6892 6893 6736 6577 6890 6728 6737 6581 6894 6732 6728 6731 6582 6737 6735 6579 6578 6731 6895 6583 6734 6733 6448 6579 6896 6897 6898 6581 6733 6894 6586 6739 6899 6735 6737 6894 6900 6901 6902 6583 6582 6735 6590 6588 6903 6738 6584 6583 6904 6591 6902 6899 6739 6738 6594 6592 6905 6899 6587 6586 6906 6595 6907 6903 6588 6587 6598 6596 6908 6903 6591 6590 6909 6910 6911 6905 6592 6591 6740 6600 6912 6905 6595 6594 6603 6740 6913 6595 6908 6596 6914 6915 6916 6908 6599 6598 6741 6605 6917 6599 6912 6600 6742 6741 6918 6912 6913 6740 6743 6742 6919 6603 6913 6604 6744 6743 6920 6604 6917 6605 6745 6744 6921 6917 6918 6741 6746 6745 6922 6918 6919 6742 6747 6746 6923 6919 6920 6743 6748 6747 6924 6744 6920 6921 6749 6748 6925 6745 6921 6922 6750 6749 6926 6746 6922 6923 6751 6750 6927 6747 6923 6924 6752 6751 6928 6748 6924 6925 6753 6752 6929 6749 6925 6926 6754 6753 6930 6750 6926 6927 6755 6754 6931 6751 6927 6928 6756 6755 6932 6752 6928 6929 6757 6756 6933 6753 6929 6930 6325 6757 6934 6754 6930 6931 6761 6325 6935 6931 6932 6755 6762 6761 6936 6932 6933 6756 6763 6762 6937 6933 6934 6757 6482 6763 6938 6934 6935 6325 6767 6482 6939 6935 6936 6761 6768 6767 6940 6936 6937 6762 6487 6768 6941 6937 6938 6763 6772 6487 6942 6939 6482 6938 6773 6772 6770 6939 6940 6767 6628 6773 6943 6940 6941 6768 6944 6629 6945 6942 6487 6941 6777 6630 6946 6770 6772 6942 6633 6777 6775 6943 6773 6770 6781 6633 6947 6629 6628 6943 6493 6781 6779 6946 6630 6629 6948 6949 6785 6775 6777 6946 6786 6635 6950 6633 6775 6947 6636 6786 6784 6779 6781 6947 6951 6637 6783 6782 6493 6779 6952 6953 6790 6635 6782 6950 6791 6640 6954 6786 6950 6784 6641 6791 6789 6637 6636 6784 6955 6642 6788 6787 6638 6637 6956 6792 6955 6640 6787 6954 6957 6958 6959 6791 6954 6789 6958 6960 6961 6641 6789 6642 6960 6962 6798 6500 6642 6792 6647 6646 6963 6502 6792 6793 6648 6647 6797 6644 6793 6794 6803 6648 6800 6645 6794 6795 6649 6803 6802 6646 6795 6963 6964 6650 6801 6647 6963 6797 6965 6652 6964 6648 6797 6800 6966 6804 6965 6803 6800 6802 6967 6805 6966 6649 6802 6650 6968 6969 6970 6651 6650 6652 6969 6971 6810 6510 6652 6804 6811 6656 6972 6512 6804 6805 6657 6811 6809 6806 6654 6805 6973 6658 6808 6807 6655 6806 6974 6812 6973 6656 6807 6972 6975 6976 6816 6811 6972 6809 6817 6661 6977 6657 6809 6658 6521 6817 6815 6812 6517 6658 6978 6979 6821 6813 6660 6812 6822 6663 6980 6661 6813 6977 6665 6822 6820 6815 6817 6977 6981 6982 6983 6818 6521 6815 6526 6824 6984 6980 6663 6818 6985 6986 6987 6820 6822 6980 6529 6826 6988 6820 6823 6665 6989 6990 6991 6984 6824 6823 6829 6828 6992 6984 6825 6526 6667 6829 6993 6825 6988 6826 6994 6995 6996 6827 6529 6988 6830 6669 6997 6827 6992 6828 6677 6830 6998 6992 6993 6829 6678 6677 6832 6993 6668 6667 6831 6678 200 6668 6997 6669 202 6831 199 6997 6998 6830 6833 202 6999 6677 6998 6832 193 6680 197 6834 193 6675 202 6833 191 199 6831 200 6835 6675 6837 6999 202 199 6838 6840 6836 6833 197 6680 6838 7000 7001 6537 6836 6682 6536 6835 6537 6835 6834 6675 6839 7002 7003 6839 6540 6681 6682 6836 6840 6839 6840 7002 6683 6540 6839 6541 6684 6685 6405 6404 6841 7004 7005 7006 6685 6842 6686 6404 7007 6842 7008 7009 7010 7007 6545 6843 739 736 7011 6545 6544 6843 6546 7012 6844 735 734 6544 7012 7013 6845 729 734 733 7013 6692 6846 6844 729 6546 7014 7015 7016 6844 7012 6845 6690 7017 6847 6845 7013 6846 7017 6697 6848 6846 6692 6691 7018 7019 7020 6691 6690 6847 6695 7021 6849 6847 7017 6848 7021 7022 6700 6697 6696 6848 7022 6852 6853 6696 6695 6849 6852 7023 6702 7021 6700 6849 7023 6856 6857 6700 7022 6853 6856 7024 6704 6852 6702 6853 7024 6860 6861 6702 7023 6857 7025 7026 6863 6856 6704 6857 6862 7027 6706 7024 6861 6704 7027 6865 6866 6860 6553 6861 7028 7029 6868 6862 6706 6553 6867 7030 6708 7027 6866 6706 7030 6870 6709 6557 6866 6865 6870 6712 6872 6867 6708 6557 7031 6710 6871 7030 6709 6708 7032 7033 7034 6870 6872 6709 7033 7035 6875 6711 6872 6712 6874 7036 6715 6562 6711 6710 7036 6877 6716 6714 6562 6873 6877 6879 6717 6715 6714 6874 6879 6720 6881 7036 6716 6715 7037 6718 6880 6877 6717 6716 7038 6721 7037 6879 6881 6717 7039 6882 7038 6719 6881 6720 7040 7041 7042 6722 6719 6718 7041 7043 7044 6569 6722 6721 7043 7045 6886 6571 6569 6882 6885 7046 6725 6573 6571 6883 7046 6888 6726 6724 6573 6884 6888 6729 6890 6885 6725 6724 7047 6727 6889 7046 6726 6725 7048 6730 7047 6888 6890 6726 7049 7050 6892 6728 6890 6729 6891 7051 6733 6731 6728 6727 7051 6736 6894 6730 6579 6731 7052 6734 6893 6891 6733 6579 7053 7054 6898 7051 6894 6733 6895 7055 6738 6735 6894 6736 7055 6897 6899 6734 6583 6735 6897 7056 6587 6895 6738 6583 7056 6902 6903 6738 7055 6899 7057 7058 7059 6897 6587 6899 6904 6907 6905 6587 7056 6903 7060 7061 7062 6902 6591 6903 6906 7063 6908 6591 6904 6905 7063 7064 6599 6907 6595 6905 7064 6911 6912 6595 6906 6908 6911 7065 6913 6908 7063 6599 7065 7066 6604 6599 7064 6912 7066 7067 6917 6912 6911 6913 7067 7068 6918 6913 7065 6604 7068 7069 6919 6917 6604 7066 7069 7070 6920 6918 6917 7067 7070 7071 6921 6918 7068 6919 7071 7072 6922 6919 7069 6920 7072 6461 6923 6920 7070 6921 6461 7073 6924 6922 6921 7071 7073 7074 6925 6923 6922 7072 7074 7075 6926 6924 6923 6461 7075 7076 6927 6925 6924 7073 7076 7077 6928 6926 6925 7074 7077 7078 6929 6927 6926 7075 7078 7079 6930 6928 6927 7076 7079 7080 6931 6929 6928 7077 7080 7081 6932 6930 6929 7078 7081 7082 6933 6931 6930 7079 7082 7083 6934 6932 6931 7080 7083 7084 6935 6933 6932 7081 7084 7085 6936 6933 7082 6934 7085 7086 6937 6934 7083 6935 7086 7087 6938 6935 7084 6936 7087 7088 6939 6937 6936 7085 7088 7089 6940 6937 7086 6938 7089 6766 6941 6938 7087 6939 6766 6771 6942 6939 7088 6940 7090 7091 7092 6940 7089 6941 6769 6945 6943 6941 6766 6942 7093 7094 7095 6771 6770 6942 6944 6776 6946 6770 6769 6943 7096 7097 7098 6945 6629 6943 6774 6780 6947 6629 6944 6946 7099 6778 7098 6776 6775 6946 6778 7100 6782 6774 6947 6775 7100 6785 6950 6780 6779 6947 7101 6783 6949 6778 6782 6779 7102 7103 6952 7100 6950 6782 6951 7104 6787 6784 6950 6785 7104 6790 6954 6783 6637 6784 7105 6788 6953 6951 6787 6637 7106 7107 7108 7104 6954 6787 7107 7109 6957 6789 6954 6790 6956 7110 6793 6642 6789 6788 7110 6959 6794 6792 6642 6955 6959 6961 6795 6793 6792 6956 6961 6798 6963 7110 6794 6793 7111 6796 6962 6959 6795 6794 7112 6799 7111 6961 6963 6795 7113 6801 7112 6797 6963 6798 7114 6964 7113 6800 6797 6796 7115 7116 7117 6802 6800 6799 7116 7118 7119 6650 6802 6801 7118 7120 6968 6652 6650 6964 6967 7121 6806 6804 6652 6965 7121 6970 6807 6805 6804 6966 6970 6810 6972 6967 6806 6805 7122 6808 6971 7121 6807 6806 7123 7124 7125 6970 6972 6807 7124 7126 6975 6809 6972 6810 6974 7127 6813 6658 6809 6808 7127 6816 6977 6973 6812 6658 7128 7129 6978 6974 6813 6812 6814 7130 6818 7127 6977 6813 7130 6821 6980 6816 6815 6977 7131 7132 6981 6814 6818 6815 6819 7133 6823 7130 6980 6818 7133 6983 6984 6821 6820 6980 6983 7134 6825 6819 6823 6820 7134 6987 6988 6823 7133 6984 6987 7135 6827 6983 6825 6984 7135 7136 6992 6825 7134 6988 7136 7137 6993 6988 6987 6827 7137 7138 6668 6827 7135 6992 7138 6996 6997 6992 7136 6993 6996 7139 6998 6993 7137 6668 7139 6672 6832 6997 6668 7138 7140 7141 7142 6997 6996 6998 198 7143 199 6998 7139 6832 7143 196 6999 200 6832 6672 7144 7145 7146 6676 7000 6837 6999 197 6833 6999 199 7143 195 206 6676 197 6999 196 7002 6838 7001 197 194 193 193 195 6675 7001 7147 7148 6835 6837 6836 6837 6675 6676 6841 7003 7149 7003 6683 6839 6840 6838 7002 7003 7002 7150 6841 6683 7003 6684 6404 6842 6253 6252 6405 6251 7151 6252 6842 7007 6843 6252 7152 7007 7153 761 735 7153 6545 7152 740 7154 6546 7153 735 6545 7155 7012 7154 735 761 733 7156 7013 7155 6546 733 740 7157 6692 7156 7012 6546 7154 7158 6690 7157 7012 7155 7013 7159 7017 7158 7013 7156 6692 7160 6697 7159 6692 7157 6690 7161 6695 7160 6690 7158 7017 7162 7021 7161 7017 7159 6697 6850 7022 7162 6697 7160 6695 7163 7164 7165 6695 7161 7021 6854 7023 6851 7021 7162 7022 7166 7167 7168 7022 6850 6852 6858 7024 6855 6852 6851 7023 7169 6859 7168 7023 6854 6856 7170 6862 6859 6855 7024 6856 6863 7027 7170 7024 6858 6860 7171 7172 7028 6859 6862 6860 7173 6867 6864 7170 7027 6862 6868 7030 7173 7027 6863 6865 7174 6869 7029 6864 6867 6865 7175 7176 7177 7173 7030 6867 7178 7032 7176 6868 6870 7030 7179 6873 7031 6869 6712 6870 7034 6874 7179 6710 6712 6871 6875 7036 7034 7031 6873 6710 7180 6876 7035 7179 6874 6873 7181 6878 7180 7034 7036 6874 7182 6880 7181 6875 6877 7036 7183 7184 7185 6876 6879 6877 7186 7187 7183 6878 6720 6879 7188 7040 7186 6718 6720 6880 7189 6883 7039 6721 6718 7037 7042 6884 7189 6882 6721 7038 7044 6885 7042 6883 6882 7039 6886 7046 7044 7189 6884 6883 7190 6887 7045 7042 6885 6884 7191 6889 7190 7044 7046 6885 7192 7193 7194 6886 6888 7046 7195 7049 7192 6887 6729 6888 7196 6891 7048 6889 6727 6729 6892 7051 7196 7047 6730 6727 7197 6893 7050 7048 6891 6730 7198 7053 7199 7196 7051 6891 7200 6895 7052 6892 6736 7051 6898 7055 7200 6893 6734 6736 7201 7202 7203 7052 6895 6734 6900 7056 6896 6895 7200 7055 7204 6901 7203 7055 6898 6897 7205 6904 6901 6896 7056 6897 7059 6907 7205 7056 6900 6902 7206 6906 7059 6901 6904 6902 7062 7063 7206 6904 7205 6907 6909 7064 7062 6907 7059 6906 7207 7208 7209 6906 7206 7063 7210 7065 6910 7063 7062 7064 7211 7066 7210 6911 7064 6909 7211 7212 7067 6911 6910 7065 6914 7068 7212 7065 7210 7066 7213 7069 6914 7067 7066 7211 7214 7070 7213 7068 7067 7212 7215 7071 7214 7069 7068 6914 7215 6462 7072 7069 7213 7070 7216 7217 7218 7071 7070 7214 7219 7073 6460 7072 7071 7215 7217 7074 7219 6461 7072 6462 7220 7075 7217 7073 6461 6460 7221 7076 7220 7074 7073 7219 7222 7077 7221 7075 7074 7217 7223 7078 7222 7076 7075 7220 7224 7079 7223 7077 7076 7221 7225 7080 7224 7078 7077 7222 7226 7081 7225 7079 7078 7223 7227 7082 7226 7080 7079 7224 7228 7083 7227 7081 7080 7225 7229 7084 7228 7082 7081 7226 7230 7085 7229 7083 7082 7227 7230 7231 7086 7083 7228 7084 7232 7087 7231 7084 7229 7085 7233 7088 7232 7086 7085 7230 6764 7089 7233 7087 7086 7231 7234 7235 7236 7087 7232 7088 7237 6771 6765 7088 7233 7089 7238 6769 7237 7089 6764 6766 7092 6945 7238 6766 6765 6771 7239 6944 7092 7237 6769 6771 7095 6776 7239 6769 7238 6945 7240 6774 7095 7092 6944 6945 7098 6780 7240 6944 7239 6776 7241 7242 7243 7095 6774 6776 6948 7100 7099 6774 7240 6780 7244 6949 7242 7098 6778 6780 7245 7102 7246 7099 7100 6778 7247 6951 7101 6948 6785 7100 6952 7104 7247 6949 6783 6785 7248 6953 7103 7101 6951 6783 7249 7106 7250 7247 7104 6951 7251 6955 7105 6952 6790 7104 7108 6956 7251 6788 6790 6953 6957 7110 7108 7105 6955 6788 7252 6958 7109 7251 6956 6955 7253 6960 7252 7108 7110 6956 7254 6962 7253 6957 6959 7110 7255 7256 7257 6958 6961 6959 7258 7259 7255 6960 6798 6961 7260 7261 7258 6796 6798 6962 7262 7115 7260 6799 6796 7111 7263 6965 7114 6801 6799 7112 7117 6966 7263 6964 6801 7113 7119 6967 7117 6965 6964 7114 6968 7121 7119 7263 6966 6965 7264 6969 7120 7117 6967 6966 7265 6971 7264 7119 7121 6967 7266 7123 7267 6968 6970 7121 7268 6973 7122 6969 6810 6970 7125 6974 7268 6808 6810 6971 6975 7127 7125 7122 6973 6808 7269 7270 7128 7268 6974 6973 7271 6814 6976 7125 7127 6974 6978 7130 7271 7127 6975 6816 7272 6979 7129 6976 6814 6816 7273 6819 6979 7271 7130 6814 6981 7133 7273 7130 6978 6821 7274 7275 7276 6979 6819 6821 6985 7134 6982 6819 7273 7133 7277 7278 7279 7133 6981 6983 7280 7135 6986 6983 6982 7134 7280 7281 7136 7134 6985 6987 6991 7137 7281 6987 6986 7135 6994 7138 6991 7136 7135 7280 7282 7283 7284 7136 7281 7137 7285 7139 6995 7137 6991 7138 7286 6672 7285 6996 7138 6994 7286 7287 198 6996 6995 7139 7288 7143 7287 7139 7285 6672 7289 196 7288 198 6672 7286 207 194 7289 198 7287 7143 7145 6676 206 7143 7288 196 7147 7000 7145 196 7289 194 7145 206 7146 207 195 194 7001 7148 7150 7148 211 7290 6837 7000 6838 7000 6676 7145 6405 7149 7291 7003 7150 7149 7002 7001 7150 7149 7150 7292 6841 7149 6405 6252 7007 6404 7293 7151 6251 7293 7009 7151 7007 7152 6545 7151 7294 7152 761 7295 737 7153 7294 7295 739 7296 7154 761 7153 7295 7296 7297 7155 740 761 737 7298 7156 7297 7154 740 739 7299 7157 7298 7155 7154 7296 7300 7158 7299 7156 7155 7297 7300 7301 7159 7156 7298 7157 7014 7160 7301 7157 7299 7158 7302 7161 7014 7159 7158 7300 7302 7303 7162 7159 7301 7160 7018 6850 7303 7160 7014 7161 7018 7304 6851 7161 7302 7162 7165 6854 7304 7162 7303 6850 7165 7305 6855 6850 7018 6851 7168 6858 7305 6851 7304 6854 7306 7307 7308 6854 7165 6855 7025 7170 7169 6855 7305 6858 7309 7026 7308 6858 7168 6859 7026 7310 6864 7169 7170 6859 7028 7173 7310 7170 7025 6863 7311 7029 7172 6863 7026 6864 7175 7312 7313 7310 7173 6864 7174 7314 6871 7028 6868 7173 7177 7031 7314 7029 6869 6868 7032 7179 7177 6869 7174 6871 7315 7033 7178 7314 7031 6871 7316 7035 7315 7177 7179 7031 7317 7318 7319 7032 7034 7179 7320 7319 7321 7033 6875 7034 7321 7322 7185 7035 6876 6875 7323 7037 7182 7180 6878 6876 7184 7038 7323 7181 6880 6878 7187 7039 7184 7037 6880 7182 7040 7189 7187 7323 7038 7037 7324 7041 7188 7184 7039 7038 7325 7043 7324 7187 7189 7039 7326 7045 7325 7040 7042 7189 7327 7328 7329 7041 7044 7042 7194 7329 7330 7043 6886 7044 7191 7331 7047 7045 6887 6886 7193 7048 7331 7190 6889 6887 7049 7196 7193 6889 7191 7047 7332 7050 7195 7331 7048 7047 7333 7334 7199 7193 7196 7048 7335 7052 7197 7049 6892 7196 7053 7200 7335 6892 7050 6893 7201 7336 7337 7197 7052 6893 7054 7338 6896 7335 7200 7052 7203 6900 7338 7200 7053 6898 7339 7340 7341 6898 7054 6896 7057 7205 7204 6896 7338 6900 7342 7343 7344 6900 7203 6901 7060 7206 7058 6901 7204 7205 7345 7346 7347 7205 7057 7059 7348 6909 7061 7059 7058 7206 7348 7349 6910 7206 7060 7062 7350 7210 7349 7062 7061 6909 7351 7211 7350 6910 6909 7348 7351 6915 7212 7210 6910 7349 7352 7353 7354 7210 7350 7211 7355 7213 6916 7212 7211 7351 7356 7214 7355 6914 7212 6915 7356 7357 7215 7213 6914 6916 7357 7358 6462 7214 7213 7355 7358 7359 6460 7356 7215 7214 7359 7218 7219 6462 7215 7357 7220 7216 7360 6460 6462 7358 7221 7360 7361 7219 6460 7359 7222 7361 7362 7217 7219 7218 7223 7362 7363 7220 7217 7216 7224 7363 7364 7221 7220 7360 7225 7364 7365 7222 7221 7361 7226 7365 7366 7223 7222 7362 7367 7368 7369 7224 7223 7363 7370 7227 7366 7225 7224 7364 7371 7228 7370 7226 7225 7365 7372 7229 7371 7227 7226 7366 7373 7230 7372 7228 7227 7370 7373 7374 7231 7229 7228 7371 7374 7375 7232 7229 7372 7230 6759 7233 7375 7231 7230 7373 7376 6764 6759 7232 7231 7374 7376 7377 6765 7232 7375 7233 7236 7237 7377 7233 6759 6764 7090 7238 7236 6765 6764 7376 7378 7379 7380 6765 7377 7237 7093 7239 7091 7237 7236 7238 7381 7382 7383 7238 7090 7092 7096 7240 7094 7092 7091 7239 7243 7384 7385 7239 7093 7095 7386 7099 7097 7094 7240 7095 7242 6948 7386 7240 7096 7098 7387 7388 7246 7098 7097 7099 7389 7101 7244 7386 6948 7099 7102 7247 7389 6948 7242 6949 7390 7103 7245 7244 7101 6949 7391 7392 7250 7389 7247 7101 7393 7105 7248 7102 6952 7247 7106 7251 7393 6952 7103 6953 7394 7107 7249 7248 7105 6953 7395 7109 7394 7393 7251 7105 7396 7397 7398 7106 7108 7251 7399 7398 7400 7107 6957 7108 7257 7400 7401 7109 6958 6957 7402 7111 7254 7252 6960 6958 7256 7112 7402 7253 6962 6960 7259 7113 7256 7254 7111 6962 7261 7114 7259 7112 7111 7402 7115 7263 7261 7256 7113 7112 7403 7116 7262 7259 7114 7113 7404 7118 7403 7261 7263 7114 7405 7120 7404 7115 7117 7263 7406 7407 7408 7116 7119 7117 7408 7409 7267 7118 6968 7119 7410 7122 7265 7120 6969 6968 7123 7268 7410 6969 7264 6971 7411 7124 7266 7265 7122 6971 7269 7412 7413 7410 7268 7122 7126 7414 6976 7123 7125 7268 7128 7271 7414 7125 7124 6975 7415 7129 7270 6975 7126 6976 7416 7417 7418 7414 7271 6976 7131 7273 7272 7271 7128 6978 7419 7132 7418 6978 7129 6979 7132 7420 6982 7272 7273 6979 7276 6985 7420 7273 7131 6981 7276 7421 6986 6981 7132 6982 7279 7280 7421 6982 7420 6985 7279 6989 7281 6986 6985 7276 7422 7423 7424 6986 7421 7280 7425 6994 6990 7281 7280 7279 7425 7426 6995 7281 6989 6991 7427 7285 7426 6991 6990 6994 7428 7286 7427 6995 6994 7425 7428 7429 7287 7285 6995 7426 7429 7430 7288 7285 7427 7286 7431 7289 7430 7287 7286 7428 7142 207 7431 7288 7287 7429 206 7142 7146 7288 7430 7289 211 7147 7144 7431 207 7289 7146 204 7144 7142 206 207 7290 210 7432 7433 7291 7434 7000 7147 7001 7147 7145 7144 6251 6253 7291 7149 7292 7291 7150 7148 7292 7292 7434 7291 6405 7291 6253 6252 7151 7152 7010 7009 7293 756 755 759 7152 7294 7153 7009 7435 7294 742 7436 7437 738 7295 7435 7011 7438 7296 737 7295 738 7438 7439 7297 736 739 737 7439 7440 7298 7296 739 7011 7441 7299 7440 7297 7296 7438 7442 7300 7441 7298 7297 7439 7442 7015 7301 7299 7298 7440 7443 7444 7445 7299 7441 7300 7446 7302 7016 7301 7300 7442 7446 7019 7303 7014 7301 7015 7447 7448 7449 7014 7016 7302 7020 7163 7304 7303 7302 7446 7450 7451 7452 7303 7019 7018 7164 7166 7305 7304 7018 7020 7306 7453 7454 7304 7163 7165 7167 7455 7169 7165 7164 7305 7308 7025 7455 7305 7166 7168 7456 7457 7458 7168 7167 7169 7309 7171 7310 7169 7455 7025 7459 7172 7456 7025 7308 7026 7312 7460 7461 7026 7309 7310 7311 7462 7174 7171 7028 7310 7462 7175 7314 7028 7172 7029 7463 7176 7313 7029 7311 7174 7464 7178 7463 7174 7462 7314 7465 7466 7467 7175 7177 7314 7318 7467 7468 7176 7032 7177 7316 7469 7180 7178 7033 7032 7469 7317 7181 7315 7035 7033 7317 7320 7182 7316 7180 7035 7185 7323 7320 7180 7469 7181 7470 7183 7322 7181 7317 7182 7471 7186 7470 7320 7323 7182 7472 7188 7471 7185 7184 7323 7473 7474 7475 7183 7187 7184 7476 7475 7477 7186 7040 7187 7328 7477 7478 7188 7041 7040 7326 7479 7190 7324 7043 7041 7479 7327 7191 7325 7045 7043 7327 7194 7331 7045 7326 7190 7480 7192 7330 7190 7479 7191 7481 7195 7480 7191 7327 7331 7333 7482 7483 7194 7193 7331 7332 7484 7197 7192 7049 7193 7199 7335 7484 7049 7195 7050 7485 7198 7334 7050 7332 7197 7198 7486 7054 7484 7335 7197 7486 7201 7338 7335 7199 7053 7339 7487 7488 7053 7198 7054 7202 7489 7204 7054 7486 7338 7341 7057 7489 7338 7201 7203 7341 7490 7058 7203 7202 7204 7344 7060 7490 7204 7489 7057 7344 7491 7061 7057 7341 7058 7347 7348 7491 7058 7490 7060 7347 7492 7349 7061 7060 7344 7492 7493 7350 7061 7491 7348 7207 7351 7493 7349 7348 7347 7207 7494 6915 7350 7349 7492 7494 7495 6916 7350 7493 7351 7496 7355 7495 6915 7351 7207 7497 7356 7496 6916 6915 7494 7497 7498 7357 7355 6916 7495 7498 7499 7358 7356 7355 7496 7499 7500 7359 7497 7357 7356 7500 7501 7218 7498 7358 7357 7501 7502 7216 7499 7359 7358 7502 7503 7360 7500 7218 7359 7503 7504 7361 7501 7216 7218 7504 7505 7362 7502 7360 7216 7505 7506 7363 7503 7361 7360 7506 7507 7364 7504 7362 7361 7507 7508 7365 7505 7363 7362 7508 7509 7366 7506 7364 7363 7509 7510 7370 7365 7364 7507 7511 7371 7510 7366 7365 7508 7369 7372 7511 7370 7366 7509 7512 7373 7369 7371 7370 7510 7512 7513 7374 7372 7371 7511 7513 6760 7375 7373 7372 7369 7514 7515 7516 7374 7373 7512 7517 7376 6758 7375 7374 7513 7517 7234 7377 6759 7375 6760 7518 7519 7520 6759 6758 7376 7521 7090 7235 7377 7376 7517 7521 7522 7091 7377 7234 7236 7380 7093 7522 7236 7235 7090 7380 7523 7094 7090 7521 7091 7383 7096 7523 7091 7522 7093 7383 7524 7097 7093 7380 7094 7524 7243 7386 7094 7523 7096 7387 7525 7526 7096 7383 7097 7241 7527 7244 7097 7524 7386 7246 7389 7527 7386 7243 7242 7528 7245 7388 7242 7241 7244 7391 7529 7530 7527 7389 7244 7390 7531 7248 7246 7102 7389 7250 7393 7531 7102 7245 7103 7532 7249 7392 7103 7390 7248 7533 7534 7535 7531 7393 7248 7397 7535 7536 7250 7106 7393 7395 7537 7252 7249 7107 7106 7537 7396 7253 7394 7109 7107 7396 7399 7254 7395 7252 7109 7399 7257 7402 7252 7537 7253 7538 7255 7401 7253 7396 7254 7539 7258 7538 7254 7399 7402 7540 7260 7539 7257 7256 7402 7541 7262 7540 7255 7259 7256 7542 7543 7544 7258 7261 7259 7545 7544 7546 7260 7115 7261 7407 7546 7547 7262 7116 7115 7405 7548 7264 7403 7118 7116 7548 7406 7265 7404 7120 7118 7267 7410 7406 7120 7405 7264 7549 7266 7409 7264 7548 7265 7412 7550 7551 7406 7410 7265 7411 7552 7126 7267 7123 7410 7552 7269 7414 7123 7266 7124 7553 7270 7413 7124 7411 7126 7416 7554 7555 7126 7552 7414 7415 7556 7272 7269 7128 7414 7418 7131 7556 7128 7270 7129 7557 7558 7559 7129 7415 7272 7419 7274 7420 7272 7556 7131 7560 7561 7562 7131 7418 7132 7275 7277 7421 7420 7132 7419 7563 7564 7565 7420 7274 7276 7278 7566 6989 7421 7276 7275 7566 7567 6990 7421 7277 7279 7424 7425 7567 6989 7279 7278 7424 7568 7426 6990 6989 7566 7568 7569 7427 6990 7567 7425 7282 7428 7569 7426 7425 7424 7282 7570 7429 7427 7426 7568 7570 7571 7430 7428 7427 7569 7571 7140 7431 7429 7428 7282 220 213 209 7430 7429 7570 204 7146 7141 7431 7430 7571 203 7144 204 7431 7140 7142 7432 7434 7290 7141 7146 7142 209 7572 7432 7148 7290 7292 7147 211 7148 211 7144 203 7433 7573 7574 7433 6251 7291 7292 7290 7434 7433 7434 7573 7293 6251 7433 7151 7009 7294 7004 7008 7010 7006 7008 7004 7294 7435 7295 7575 7435 7008 743 7576 7011 744 738 7575 7576 7577 7438 736 738 744 7577 7578 7439 743 7011 736 7578 7579 7440 7576 7438 7011 7579 7580 7441 7439 7438 7577 730 7442 7580 7440 7439 7578 730 7581 7015 7441 7440 7579 7581 7582 7016 7441 7580 7442 7583 7446 7582 7015 7442 730 7583 7584 7019 7016 7015 7581 7584 7585 7020 7016 7582 7446 7585 7447 7163 7019 7446 7583 7447 7586 7164 7019 7584 7020 7586 7450 7166 7163 7020 7585 7450 7587 7167 7163 7447 7164 7587 7306 7455 7166 7164 7586 7588 7457 7589 7166 7450 7167 7307 7590 7309 7167 7587 7455 7590 7456 7171 7455 7306 7308 7591 7460 7592 7308 7307 7309 7459 7593 7311 7309 7590 7171 7593 7312 7462 7171 7456 7172 7461 7594 7313 7172 7459 7311 7595 7596 7597 7311 7593 7462 7598 7466 7596 7462 7312 7175 7464 7599 7315 7313 7176 7175 7599 7465 7316 7463 7178 7176 7465 7318 7469 7178 7464 7315 7468 7600 7319 7315 7599 7316 7600 7601 7321 7316 7465 7469 7601 7602 7322 7469 7318 7317 7603 7604 7605 7317 7319 7320 7606 7607 7604 7320 7321 7185 7608 7474 7607 7322 7183 7185 7472 7609 7324 7470 7186 7183 7609 7473 7325 7471 7188 7186 7473 7476 7326 7472 7324 7188 7476 7328 7479 7324 7609 7325 7478 7610 7329 7325 7473 7326 7610 7611 7330 7326 7476 7479 7612 7613 7614 7479 7328 7327 7615 7482 7613 7327 7329 7194 7481 7616 7332 7330 7192 7194 7616 7333 7484 7192 7480 7195 7483 7617 7334 7195 7481 7332 7618 7619 7620 7332 7616 7484 7485 7336 7486 7199 7484 7333 7619 7621 7337 7199 7334 7198 7337 7622 7202 7198 7485 7486 7622 7339 7489 7201 7486 7336 7623 7624 7625 7201 7337 7202 7340 7342 7490 7489 7202 7622 7626 7627 7628 7489 7339 7341 7343 7345 7491 7490 7341 7340 7629 7630 7631 7490 7342 7344 7346 7632 7492 7491 7344 7343 7632 7208 7493 7347 7491 7345 7633 7634 7635 7492 7347 7346 7209 7636 7494 7493 7492 7632 7636 7637 7495 7207 7493 7208 7637 7638 7496 7494 7207 7209 7639 7497 7638 7495 7494 7636 7639 7640 7498 7496 7495 7637 7640 7641 7499 7497 7496 7638 7641 7642 7500 7639 7498 7497 7642 7643 7501 7640 7499 7498 7643 7644 7502 7641 7500 7499 7644 7645 7503 7642 7501 7500 7645 7646 7504 7643 7502 7501 7646 7647 7505 7644 7503 7502 7647 7648 7506 7645 7504 7503 7648 7649 7507 7646 7505 7504 7649 7650 7508 7647 7506 7505 7650 7651 7509 7648 7507 7506 7651 7652 7510 7649 7508 7507 7652 7367 7511 7509 7508 7650 7653 7654 7655 7510 7509 7651 7656 7512 7368 7511 7510 7652 7656 7657 7513 7369 7511 7367 7657 7658 6760 7512 7369 7368 7658 7659 6758 7513 7512 7656 7660 7517 7659 6760 7513 7657 7660 7661 7234 6758 6760 7658 7661 7662 7235 6758 7659 7517 7520 7521 7662 7234 7517 7660 7520 7378 7522 7235 7234 7661 7663 7664 7665 7235 7662 7521 7379 7381 7523 7522 7521 7520 7666 7667 7668 7522 7378 7380 7382 7384 7524 7523 7380 7379 7667 7669 7385 7523 7381 7383 7385 7670 7241 7383 7382 7524 7670 7387 7527 7243 7524 7384 7671 7388 7526 7243 7385 7241 7672 7529 7673 7241 7670 7527 7528 7674 7390 7387 7246 7527 7674 7391 7531 7246 7388 7245 7530 7675 7392 7245 7528 7390 7676 7534 7677 7390 7674 7531 7532 7678 7394 7531 7391 7250 7678 7533 7395 7392 7249 7250 7533 7397 7537 7249 7532 7394 7536 7679 7398 7394 7678 7395 7679 7680 7400 7395 7533 7537 7680 7681 7401 7537 7397 7396 7682 7683 7684 7396 7398 7399 7685 7686 7683 7399 7400 7257 7687 7688 7686 7401 7255 7257 7689 7543 7688 7538 7258 7255 7541 7690 7403 7539 7260 7258 7690 7542 7404 7540 7262 7260 7542 7545 7405 7541 7403 7262 7545 7407 7548 7403 7690 7404 7547 7691 7408 7404 7542 7405 7692 7409 7691 7405 7545 7548 7693 7550 7694 7548 7407 7406 7549 7695 7411 7408 7267 7406 7695 7412 7552 7267 7409 7266 7551 7696 7413 7266 7549 7411 7697 7554 7698 7411 7695 7552 7553 7699 7415 7552 7412 7269 7699 7416 7556 7269 7413 7270 7700 7558 7701 7270 7553 7415 7417 7702 7419 7415 7699 7556 7702 7557 7274 7556 7416 7418 7557 7703 7275 7418 7417 7419 7703 7560 7277 7274 7419 7702 7560 7704 7278 7274 7557 7275 7704 7563 7566 7277 7275 7703 7563 7422 7567 7278 7277 7560 7705 7706 7707 7566 7278 7704 7423 7708 7568 7567 7566 7563 7708 7283 7569 7424 7567 7422 7709 7710 7711 7568 7424 7423 7284 7712 7570 7569 7568 7708 7712 7713 7571 7282 7569 7283 7713 7714 7140 7284 7570 7282 7714 7715 7141 7712 7571 7570 7715 205 204 7140 7571 7713 203 205 208 7141 7140 7714 208 205 7716 7141 7715 204 7432 7572 7573 7572 213 212 211 210 7290 210 203 208 7010 7574 7717 7574 7293 7433 7434 7432 7573 7574 7573 7718 7010 7293 7574 7008 7435 7009 7719 7006 7005 7719 747 7006 7435 7575 738 7720 7575 7006 742 7437 7576 741 744 7720 7437 7721 7577 741 743 744 7721 7722 7578 742 7576 743 7722 7723 7579 7437 7577 7576 7723 731 7580 7721 7578 7577 732 7724 7725 7579 7578 7722 732 7725 7581 7580 7579 7723 7725 7726 7582 731 730 7580 7726 7727 7583 7581 730 732 7727 7728 7584 7582 7581 7725 7728 7448 7585 7583 7582 7726 7729 7730 7731 7584 7583 7727 7449 7451 7586 7585 7584 7728 7732 7733 7734 7447 7585 7448 7452 7453 7587 7586 7447 7449 7735 7733 7588 7450 7586 7451 7454 7589 7307 7450 7452 7587 7589 7457 7590 7306 7587 7453 7736 7737 7591 7306 7454 7307 7458 7592 7459 7307 7589 7590 7592 7460 7593 7456 7590 7457 7738 7739 7740 7456 7458 7459 7740 7741 7595 7459 7592 7593 7594 7597 7463 7593 7460 7312 7597 7596 7464 7312 7461 7313 7596 7466 7599 7313 7594 7463 7467 7466 7742 7463 7597 7464 7743 7744 7745 7464 7596 7599 7745 7746 7747 7599 7466 7465 7747 7748 7749 7465 7467 7318 7749 7750 7603 7318 7468 7319 7602 7605 7470 7319 7600 7321 7605 7604 7471 7321 7601 7322 7604 7607 7472 7602 7470 7322 7607 7474 7609 7470 7605 7471 7475 7474 7751 7471 7604 7472 7477 7475 7752 7472 7607 7609 7753 7754 7755 7609 7474 7473 7755 7756 7757 7473 7475 7476 7757 7758 7612 7476 7477 7328 7611 7614 7480 7328 7478 7329 7614 7613 7481 7329 7610 7330 7613 7482 7616 7330 7611 7480 7759 7760 7761 7480 7614 7481 7762 7763 7764 7481 7613 7616 7617 7620 7485 7616 7482 7333 7620 7619 7336 7334 7333 7483 7765 7766 7767 7334 7617 7485 7621 7487 7622 7336 7485 7620 7768 7766 7623 7337 7336 7619 7488 7625 7340 7337 7621 7622 7625 7624 7342 7339 7622 7487 7624 7628 7343 7339 7488 7340 7628 7627 7345 7342 7340 7625 7627 7769 7346 7342 7624 7343 7769 7770 7632 7345 7343 7628 7770 7771 7208 7346 7345 7627 7771 7772 7209 7632 7346 7769 7772 7773 7636 7208 7632 7770 7773 7774 7637 7209 7208 7771 7774 7775 7638 7772 7636 7209 7775 7776 7639 7637 7636 7773 7776 7352 7640 7638 7637 7774 7352 7354 7641 7639 7638 7775 7354 7777 7642 7776 7640 7639 7777 7778 7643 7352 7641 7640 7778 7779 7644 7354 7642 7641 7779 7780 7645 7777 7643 7642 7780 7781 7646 7778 7644 7643 7781 7782 7647 7779 7645 7644 7782 7783 7648 7780 7646 7645 7783 7784 7649 7781 7647 7646 7784 7785 7650 7782 7648 7647 7785 7786 7651 7783 7649 7648 7786 7787 7652 7784 7650 7649 7787 7788 7367 7785 7651 7650 7788 7789 7368 7786 7652 7651 7789 7790 7656 7367 7652 7787 7790 7791 7657 7368 7367 7788 7791 7792 7658 7656 7368 7789 7792 7793 7659 7790 7657 7656 7793 7794 7660 7658 7657 7791 7794 7795 7661 7659 7658 7792 7795 7518 7662 7660 7659 7793 7796 7797 7798 7661 7660 7794 7519 7799 7378 7662 7661 7795 7799 7665 7379 7520 7662 7518 7665 7664 7381 7378 7520 7519 7664 7668 7382 7378 7799 7379 7668 7667 7384 7381 7379 7665 7800 7801 7802 7381 7664 7382 7669 7525 7670 7384 7382 7668 7803 7801 7804 7385 7384 7667 7805 7806 7807 7385 7669 7670 7671 7673 7528 7670 7525 7387 7673 7529 7674 7388 7387 7526 7808 7809 7810 7388 7671 7528 7811 7812 7813 7528 7673 7674 7675 7677 7532 7674 7529 7391 7677 7534 7678 7392 7391 7530 7535 7534 7814 7392 7675 7532 7815 7816 7817 7532 7677 7678 7817 7818 7819 7678 7534 7533 7819 7820 7821 7533 7535 7397 7821 7822 7682 7397 7536 7398 7681 7684 7538 7398 7679 7400 7684 7683 7539 7400 7680 7401 7683 7686 7540 7681 7538 7401 7686 7688 7541 7684 7539 7538 7688 7543 7690 7539 7683 7540 7544 7543 7823 7540 7686 7541 7824 7825 7826 7541 7688 7690 7826 7827 7828 7690 7543 7542 7828 7829 7830 7542 7544 7545 7831 7832 7833 7545 7546 7407 7692 7694 7549 7407 7547 7408 7694 7550 7695 7408 7691 7409 7551 7550 7834 7409 7692 7549 7835 7836 7697 7549 7694 7695 7696 7698 7553 7695 7550 7412 7698 7554 7699 7413 7412 7551 7837 7838 7700 7413 7696 7553 7555 7701 7417 7553 7698 7699 7701 7558 7702 7416 7699 7554 7839 7840 7841 7416 7555 7417 7559 7561 7703 7702 7417 7701 7842 7843 7844 7557 7702 7558 7562 7564 7704 7703 7557 7559 7845 7846 7847 7560 7703 7561 7565 7848 7422 7704 7560 7562 7848 7849 7423 7563 7704 7564 7849 7850 7708 7422 7563 7565 7850 7851 7283 7423 7422 7848 7851 7852 7284 7708 7423 7849 7852 7853 7712 7283 7708 7850 7853 7854 7713 7284 7283 7851 7854 7855 7714 7852 7712 7284 7855 7856 7715 7853 7713 7712 7856 7716 205 7854 7714 7713 7716 220 208 7715 7714 7855 7857 215 7858 7715 7856 205 212 214 215 7859 7717 216 210 209 7432 208 220 209 7004 7717 7859 7574 7718 7717 7573 7572 7718 7718 216 7717 7010 7717 7004 7008 7006 7575 745 747 7719 752 228 758 7575 7720 744 7720 747 7860 7437 7861 7721 748 741 7860 7862 7863 7864 748 7436 742 7722 7721 7865 7436 7861 7437 7723 7722 7866 7861 7865 7721 731 7723 7867 7865 7866 7722 732 731 7868 7867 7723 7866 7869 7870 7871 7868 731 7867 7726 7725 7872 7868 7724 732 7727 7726 7873 7724 7872 7725 7728 7727 7874 7873 7726 7872 7448 7728 7445 7874 7727 7873 7449 7448 7444 7445 7728 7874 7451 7449 7875 7444 7448 7445 7452 7451 7876 7875 7449 7444 7453 7452 7877 7876 7451 7875 7454 7453 7878 7877 7452 7876 7589 7454 7735 7878 7453 7877 7879 7880 7881 7735 7454 7878 7458 7457 7882 7589 7735 7588 7592 7458 7736 7882 7457 7588 7883 7884 7739 7736 7458 7882 7461 7460 7885 7592 7736 7591 7594 7461 7738 7460 7591 7885 7597 7594 7740 7738 7461 7885 7886 7887 7888 7740 7594 7738 7888 7889 7890 7597 7740 7595 7891 7892 7893 7596 7595 7598 7468 7467 7894 7466 7598 7742 7600 7468 7743 7467 7742 7894 7601 7600 7745 7468 7894 7743 7602 7601 7747 7600 7743 7745 7605 7602 7749 7747 7601 7745 7895 7896 7897 7749 7602 7747 7897 7898 7899 7605 7749 7603 7899 7900 7901 7604 7603 7606 7901 7902 7903 7607 7606 7608 7903 7904 7754 7474 7608 7751 7478 7477 7905 7475 7751 7752 7610 7478 7753 7477 7752 7905 7611 7610 7755 7478 7905 7753 7614 7611 7757 7755 7610 7753 7906 7907 7908 7757 7611 7755 7908 7909 7760 7614 7757 7612 7483 7482 7910 7613 7612 7615 7617 7483 7759 7482 7615 7910 7620 7617 7761 7759 7483 7910 7911 7912 7913 7761 7617 7759 7621 7619 7914 7620 7761 7618 7487 7621 7915 7914 7619 7618 7488 7487 7916 7915 7621 7914 7625 7488 7768 7916 7487 7915 7917 7918 7919 7768 7488 7916 7628 7624 7920 7623 7625 7768 7921 7922 7923 7920 7624 7623 7769 7627 7924 7626 7628 7920 7770 7769 7925 7924 7627 7626 7771 7770 7926 7925 7769 7924 7772 7771 7927 7925 7926 7770 7773 7772 7928 7927 7771 7926 7774 7773 7929 7928 7772 7927 7775 7774 7930 7928 7929 7773 7776 7775 7931 7929 7930 7774 7352 7776 7932 7931 7775 7930 7933 7934 7935 7932 7776 7931 7777 7354 7936 7932 7353 7352 7778 7777 7935 7353 7936 7354 7779 7778 7934 7936 7935 7777 7780 7779 7937 7935 7934 7778 7781 7780 7938 7934 7937 7779 7782 7781 7939 7937 7938 7780 7783 7782 7940 7938 7939 7781 7784 7783 7941 7939 7940 7782 7785 7784 7942 7940 7941 7783 7786 7785 7943 7941 7942 7784 7787 7786 7944 7942 7943 7785 7788 7787 7945 7943 7944 7786 7789 7788 7946 7944 7945 7787 7790 7789 7947 7945 7946 7788 7791 7790 7948 7947 7789 7946 7792 7791 7949 7948 7790 7947 7793 7792 7950 7948 7949 7791 7794 7793 7951 7949 7950 7792 7795 7794 7952 7951 7793 7950 7518 7795 7953 7952 7794 7951 7519 7518 7954 7953 7795 7952 7799 7519 7955 7954 7518 7953 7665 7799 7956 7954 7955 7519 7957 7958 7959 7956 7799 7955 7668 7664 7960 7663 7665 7956 7961 7962 7957 7960 7664 7663 7669 7667 7963 7668 7960 7666 7525 7669 7964 7963 7667 7666 7526 7525 7965 7964 7669 7963 7671 7526 7803 7525 7964 7965 7673 7671 7804 7803 7526 7965 7966 7967 7968 7804 7671 7803 7530 7529 7969 7673 7804 7672 7675 7530 7808 7529 7672 7969 7677 7675 7810 7808 7530 7969 7812 7970 7971 7810 7675 7808 7971 7972 7816 7677 7810 7676 7536 7535 7973 7534 7676 7814 7679 7536 7815 7535 7814 7973 7680 7679 7817 7536 7973 7815 7681 7680 7819 7679 7815 7817 7684 7681 7821 7819 7680 7817 7974 7975 7976 7821 7681 7819 7976 7977 7978 7684 7821 7682 7978 7979 7980 7683 7682 7685 7980 7981 7982 7686 7685 7687 7982 7983 7825 7688 7687 7689 7546 7544 7984 7543 7689 7823 7547 7546 7824 7544 7823 7984 7691 7547 7826 7546 7984 7824 7692 7691 7828 7547 7824 7826 7694 7692 7830 7828 7691 7826 7831 7985 7986 7830 7692 7828 7987 7988 7989 7694 7830 7693 7696 7551 7990 7550 7693 7834 7698 7696 7835 7990 7551 7834 7991 7992 7838 7835 7696 7990 7555 7554 7993 7698 7835 7697 7701 7555 7837 7993 7554 7697 7994 7995 7996 7837 7555 7993 7559 7558 7997 7701 7837 7700 7561 7559 7998 7997 7558 7700 7562 7561 7999 7998 7559 7997 7564 7562 8000 7999 7561 7998 7565 7564 8001 8000 7562 7999 7848 7565 8002 8001 7564 8000 7849 7848 8003 8001 8002 7565 7850 7849 8004 8003 7848 8002 7851 7850 8005 8004 7849 8003 7852 7851 8006 8004 8005 7850 7853 7852 8007 8006 7851 8005 7854 7853 8008 8007 7852 8006 7855 7854 7709 8007 8008 7853 7856 7855 7711 8008 7709 7854 7716 7856 8009 7709 7711 7855 220 7716 218 7711 8009 7856 213 220 219 8009 218 7716 7857 8010 215 7572 212 7718 209 213 7572 213 219 214 7859 8010 8011 7005 7004 7859 7718 212 216 7859 216 8010 7719 7005 7859 7006 747 7720 753 746 745 748 8012 7436 7720 7860 741 8013 7860 746 7861 7436 8014 8013 8012 748 7865 7861 8015 7436 8012 8014 7866 7865 8016 8014 8015 7861 7866 8017 7867 8015 8016 7865 7867 7863 7868 8016 8017 7866 7868 7862 7724 8017 7863 7867 7872 7724 8018 7863 7862 7868 7873 7872 8019 7862 8018 7724 7873 8020 7874 8018 8019 7872 7874 8021 7445 8019 8020 7873 8022 8023 8024 8021 7874 8020 7444 8025 7875 8021 7443 7445 7876 7875 8026 8025 7444 7443 7876 7731 7877 8025 8026 7875 7878 7877 7730 7731 7876 8026 7878 7734 7735 7731 7730 7877 8027 7881 8028 7734 7878 7730 7588 8029 7882 7733 7735 7734 7882 8030 7736 8029 7588 7733 8031 8032 8033 8030 7882 8029 7591 8034 7885 7737 7736 8030 7885 7883 7738 8034 7591 7737 8035 8036 8037 7883 7885 8034 8038 8039 8040 7739 7738 7883 7595 8041 7598 7741 7740 7739 7598 7886 7742 7595 7741 8041 7742 7888 7894 7598 8041 7886 7894 7890 7743 7888 7742 7886 7891 8042 8043 7890 7894 7888 8042 8044 8045 7744 7743 7890 8044 8046 8047 7746 7745 7744 8048 8049 8050 7748 7747 7746 7603 8051 7606 7750 7749 7748 7606 7895 7608 7603 7750 8051 7608 7897 7751 7606 8051 7895 7751 7899 7752 7608 7895 7897 7752 7901 7905 7751 7897 7899 7905 7903 7753 7901 7752 7899 8052 8053 8054 7903 7905 7901 8053 8055 8056 7754 7753 7903 8057 8058 8059 7756 7755 7754 7612 8060 7615 7758 7757 7756 7615 7906 7910 7612 7758 8060 7910 7908 7759 7906 7615 8060 8061 8062 8063 7908 7910 7906 7618 7761 8064 7760 7759 7908 7618 7764 7914 8064 7761 7760 7914 7763 7915 7764 7618 8064 7916 7915 8065 7763 7914 7764 7916 7767 7768 7763 8065 7915 8066 8067 8068 7767 7916 8065 7623 8069 7920 7766 7768 7767 7920 8070 7626 8069 7623 7766 7626 8071 7924 8070 7920 8069 7924 8072 7925 8071 7626 8070 7925 8073 7926 8071 8072 7924 7927 7926 8074 8073 7925 8072 7927 8075 7928 8073 8074 7926 7928 8076 7929 8074 8075 7927 7930 7929 8077 8076 7928 8075 7930 8078 7931 8076 8077 7929 7931 8079 7932 8077 8078 7930 7932 8080 7353 8078 8079 7931 7936 7353 8081 8079 8080 7932 7935 7936 8082 8080 8081 7353 8083 7937 7934 8081 8082 7936 8084 7938 7937 8082 7933 7935 8085 8086 8087 7933 8083 7934 7938 8088 7939 8083 8084 7937 8085 7941 7940 8084 8088 7938 8089 7942 7941 8088 8086 7939 8090 7943 7942 8086 8085 7940 8091 7944 7943 8085 8089 7941 8092 8093 8094 8089 8090 7942 7944 8095 7945 8090 8091 7943 7945 8093 7946 8091 8095 7944 7946 8092 7947 8095 8093 7945 7947 8096 7948 8093 8092 7946 7948 8097 7949 8092 8096 7947 7950 7949 8098 8097 7948 8096 7950 8099 7951 8097 8098 7949 7951 8100 7952 8098 8099 7950 7952 8101 7953 8099 8100 7951 7954 7953 8102 8101 7952 8100 7954 7515 7955 8101 8102 7953 7956 7955 7514 7515 7954 8102 7956 8103 7663 7515 7514 7955 7663 8104 7960 8103 7956 7514 7960 8105 7666 8104 7663 8103 7666 8106 7963 8105 7960 8104 7963 8107 7964 8106 7666 8105 7965 7964 8108 8107 7963 8106 7965 7802 7803 8107 8108 7964 8109 8110 8111 7802 7965 8108 7672 7804 8112 7801 7803 7802 7672 7807 7969 8112 7804 7801 7969 7806 7808 7807 7672 8112 7966 8113 8114 7806 7969 7807 7676 7810 8115 7809 7808 7806 7676 7813 7814 8115 7810 7809 7814 7812 7973 7676 8115 7813 7973 7971 7815 7812 7814 7813 8116 8117 8118 7971 7973 7812 8117 8119 8120 7816 7815 7971 8119 8121 8122 7818 7817 7816 8121 8123 8124 7820 7819 7818 7682 8125 7685 7822 7821 7820 7685 7974 7687 8125 7682 7822 7687 7976 7689 7685 8125 7974 7689 7978 7823 7687 7974 7976 7823 7980 7984 7689 7976 7978 7984 7982 7824 7980 7823 7978 8126 8127 8128 7982 7984 7980 8127 8129 8130 7825 7824 7982 8129 8131 8132 7827 7826 7825 7693 7830 8133 7829 7828 7827 7693 7832 7834 8133 7830 7829 7834 7831 7990 7693 8133 7832 7990 7986 7835 7831 7834 7832 8134 8135 8136 7986 7990 7831 7697 8137 7993 7836 7835 7986 7993 7991 7837 8137 7697 7836 8138 7996 8139 7991 7993 8137 7700 8140 7997 7838 7837 7991 7997 8141 7998 8140 7700 7838 7999 7998 8142 8141 7997 8140 7999 7841 8000 8141 8142 7998 8001 8000 7840 7841 7999 8142 8001 7844 8002 7841 7840 8000 8003 8002 7843 7844 8001 7840 8003 8143 8004 7844 7843 8002 8004 8144 8005 7843 8143 8003 8006 8005 8145 8144 8004 8143 8006 8146 8007 8144 8145 8005 8007 8147 8008 8145 8146 8006 7709 8008 8148 8147 8007 8146 8149 8150 8151 8147 8148 8008 7711 8152 8009 8148 7710 7709 8009 8150 218 7710 8152 7711 218 8149 219 8152 8150 8009 219 8153 214 8150 8149 218 214 7858 215 8153 219 8149 8154 231 7857 7858 214 8153 745 8011 8155 8011 7719 7859 216 215 8010 8011 8010 8156 745 7719 8011 747 746 7860 228 752 753 8012 750 8014 7860 8013 748 752 8157 8013 8015 8014 749 8157 750 8012 8016 8015 8158 8014 750 749 8017 8016 8159 8015 749 8158 7863 8017 8160 8158 8159 8016 8161 8162 8163 8159 8160 8017 7862 8164 8018 8160 7864 7863 8019 8018 8165 7864 8164 7862 8020 8019 8166 8018 8164 8165 8021 8020 8167 8165 8166 8019 8021 8168 7443 8166 8167 8020 8025 7443 8169 8168 8021 8167 8025 8170 8026 8168 8169 7443 7731 8026 8171 8169 8170 8025 8172 8173 8174 8170 8171 8026 7734 7730 8175 8171 7729 7731 8172 8176 8177 7729 8175 7730 8029 7733 8178 7732 7734 8175 8029 8179 8030 7732 8178 7733 7737 8030 8180 8179 8029 8178 8034 7737 7880 8180 8030 8179 8034 8181 7883 8180 7880 7737 8031 8182 8035 8181 8034 7880 7741 7739 8183 7884 7883 8181 8041 7741 8037 8183 7739 7884 8041 8184 7886 8183 8037 7741 8038 8185 8186 8184 8041 8037 8185 8187 7893 7887 7886 8184 7744 7890 8188 7889 7888 7887 7746 7744 7892 8188 7890 7889 7748 7746 8043 7892 7744 8188 7750 7748 8045 8043 7746 7892 8051 7750 8047 8045 7748 8043 8051 8189 7895 8045 8047 7750 8048 8190 8191 8189 8051 8047 8190 8192 8193 7896 7895 8189 8192 8194 8195 7898 7897 7896 8194 8196 8197 7900 7899 7898 8196 8198 8052 7902 7901 7900 7756 7754 8199 7904 7903 7902 7758 7756 8054 8199 7754 7904 8060 7758 8056 8054 7756 8199 8060 8200 7906 8054 8056 7758 8057 8201 8202 8200 8060 8056 8201 8203 8061 7907 7906 8200 8064 7760 8204 7909 7908 7907 7764 8064 8063 7909 8204 7760 8205 8206 7913 8204 8063 8064 8065 7763 8207 7762 7764 8063 7767 8065 7912 7762 8207 7763 8208 8209 8210 8207 7912 8065 8069 7766 8211 7765 7767 7912 8069 8212 8070 7765 8211 7766 8071 8070 8213 8212 8069 8211 8071 8214 8072 8212 8213 8070 8073 8072 8215 8214 8071 8213 8073 8216 8074 8214 8215 8072 8075 8074 8217 8215 8216 8073 8076 8075 8218 8216 8217 8074 8076 8219 8077 8217 8218 8075 8078 8077 8220 8218 8219 8076 8079 8078 8221 8219 8220 8077 8079 8222 8080 8220 8221 8078 8080 7635 8081 8221 8222 8079 8082 8081 8223 8222 7635 8080 7933 8082 8224 8081 7635 8223 8083 7933 8225 8082 8223 8224 8084 8083 8226 7933 8224 8225 8088 8084 8227 8083 8225 8226 8086 8088 8228 8226 8227 8084 7939 8086 7940 8088 8227 8228 8089 8085 8229 8086 8228 8087 8090 8089 8230 8085 8087 8229 8091 8090 8231 8089 8229 8230 8095 8091 8232 8090 8230 8231 8093 8095 8233 8231 8232 8091 8234 8096 8092 8232 8233 8095 8235 8236 8237 8233 8094 8093 8096 8238 8097 8094 8234 8092 8097 8239 8098 8234 8238 8096 8099 8098 8240 8238 8239 8097 8100 8099 8241 8239 8240 8098 8100 8242 8101 8240 8241 8099 8101 7653 8102 8241 8242 8100 7515 8102 8243 8242 7653 8101 8244 8245 8246 7653 8243 8102 8103 7514 8247 8243 7516 7515 8104 8103 8248 7516 8247 7514 8104 8249 8105 8247 8248 8103 8106 8105 8250 8249 8104 8248 8106 8251 8107 8249 8250 8105 8108 8107 8252 8251 8106 8250 7802 8108 7962 8251 8252 8107 8253 8254 8109 8252 7962 8108 8112 7801 8255 7800 7802 7962 7807 8112 8111 7800 8255 7801 8256 8257 7968 8255 8111 8112 7809 7806 8258 7805 7807 8111 8115 7809 7967 8258 7806 7805 7813 8115 8114 8258 7967 7809 8259 8260 8261 7967 8114 8115 8260 8262 8263 7811 7813 8114 8262 8264 8116 7970 7812 7811 7818 7816 8265 7972 7971 7970 7820 7818 8118 8265 7816 7972 7822 7820 8120 8118 7818 8265 8125 7822 8122 8120 7820 8118 7974 8125 8124 8120 8122 7822 8266 8267 8268 8122 8124 8125 8267 8269 8270 7975 7974 8124 8269 8271 8272 7977 7976 7975 8271 8273 8274 7979 7978 7977 8273 8275 8126 7981 7980 7979 7827 7825 8276 7983 7982 7981 7829 7827 8128 8276 7825 7983 8133 7829 8130 8128 7827 8276 7832 8133 8132 8128 8130 7829 8277 8278 8279 8130 8132 8133 8278 8280 7989 7833 7832 8132 7836 7986 8281 7985 7831 7833 8137 7836 7988 8281 7986 7985 8137 8282 7991 8281 7988 7836 8134 8283 8284 8282 8137 7988 8140 7838 8285 7992 7991 8282 8140 8286 8141 7992 8285 7838 8142 8141 8287 8286 8140 8285 7841 8142 7995 8286 8287 8141 8288 8289 8290 8287 7995 8142 7844 7840 8291 7995 7839 7841 8292 8293 8294 7839 8291 7840 8143 7843 8295 8291 7842 7844 8144 8143 8296 7842 8295 7843 8144 8297 8145 8295 8296 8143 8146 8145 8298 8296 8297 8144 8147 8146 8299 8297 8298 8145 8147 8300 8148 8298 8299 8146 7710 8148 8301 8299 8300 8147 8152 7710 8302 8148 8300 8301 8150 8152 8303 8301 8302 7710 8304 8305 8306 8302 8303 8152 8149 8307 8153 8303 8151 8150 8153 8306 7858 8151 8307 8149 7858 8154 7857 8307 8306 8153 7857 231 8156 8154 7858 8306 753 8155 227 8011 8156 8155 8010 7857 8156 8155 8156 8308 745 8155 753 746 752 8013 224 758 228 8309 8310 8311 8013 8157 8012 758 757 8157 8158 749 8310 757 751 750 8312 8310 8309 749 751 8310 8312 8313 8159 8159 8158 8312 8313 8314 8160 8160 8159 8313 8314 8315 7864 7864 8160 8314 8315 8316 8164 7864 8315 8164 8316 8317 8165 8164 8316 8165 8317 8318 8166 8166 8165 8317 8318 8319 8167 8167 8166 8318 8319 8320 8168 8167 8319 8168 8320 7871 8169 8168 8320 8169 7871 8321 8170 8169 7871 8170 8321 8023 8171 8170 8321 8171 8023 8322 7729 8171 8023 7729 8322 8323 8175 7729 8322 8175 8323 8324 7732 8175 8323 7732 8324 8177 8178 7732 8324 8178 8177 8325 8179 8178 8177 8179 8325 7881 8180 8179 8325 8180 8326 8033 8327 8180 7881 7880 7879 8328 8181 7880 7879 8181 8328 8032 7884 8328 7884 8181 8032 8035 8183 7884 8032 8183 8329 8040 8330 8183 8035 8037 8036 8331 8184 8037 8036 8184 8331 8039 7887 8331 7887 8184 8039 8186 7889 8039 7889 7887 8186 7893 8188 7889 8186 8188 7891 8187 8332 8188 7893 7892 8333 8334 8335 7892 7891 8043 8336 8337 8338 8043 8042 8045 8339 8050 8340 8045 8044 8047 8046 8341 8189 8047 8046 8189 8341 8049 7896 8189 8341 7896 8049 8191 7898 8049 7898 7896 8191 8193 7900 8191 7900 7898 8193 8195 7902 8193 7902 7900 8195 8197 7904 8195 7904 7902 8197 8052 8199 7904 8197 8199 8342 8343 8344 8199 8052 8054 8345 8059 8346 8054 8053 8056 8055 8347 8200 8056 8055 8200 8347 8058 7907 8347 7907 8200 8058 8202 7909 8058 7909 7907 8202 8061 8204 7909 8202 8204 8348 8205 8349 8204 8061 8063 8062 8350 7762 8063 8062 7762 8350 7913 8207 7762 8350 8207 8351 8208 8352 8207 7913 7912 7911 8353 7765 7912 7911 7765 8353 8210 8211 7765 8353 8211 8210 8354 8212 8211 8210 8212 8354 8067 8213 8212 8354 8213 8067 8355 8214 8213 8067 8214 8355 7917 8215 8214 8355 8215 7917 8356 8216 8215 7917 8216 8356 7921 8217 8216 8356 8217 7921 8357 8218 8218 8217 7921 8357 8358 8219 8218 8357 8219 8358 7629 8220 8219 8358 8220 7629 8359 8221 8221 8220 7629 8359 7633 8222 8221 8359 8222 8360 8361 8362 8222 7633 7635 7634 8361 8223 7635 7634 8223 8361 8363 8224 8224 8223 8361 8363 8364 8225 8225 8224 8363 8364 8365 8226 8226 8225 8364 8365 8366 8227 8227 8226 8365 8366 8367 8228 8228 8227 8366 8367 8368 8087 8087 8228 8367 8368 8369 8229 8229 8087 8368 8369 8370 8230 8230 8229 8369 8370 8371 8231 8231 8230 8370 8371 8372 8232 8232 8231 8371 8372 8373 8233 8233 8232 8372 8373 8374 8094 8094 8233 8373 8374 8375 8234 8234 8094 8374 8375 8376 8238 8234 8375 8238 8239 8377 8240 8238 8376 8239 8378 8377 8237 8239 8376 8377 8378 8379 8241 8241 8240 8378 8379 7654 8242 8241 8379 8242 8380 8381 8382 8242 7654 7653 7655 8381 8243 7653 7655 8243 8381 8383 7516 8243 8381 7516 8383 8384 8247 7516 8383 8247 8384 8385 8248 8248 8247 8384 8385 8386 8249 8248 8385 8249 8386 7798 8250 8249 8386 8250 7798 8387 8251 8250 7798 8251 8387 7957 8252 8251 8387 8252 8388 8253 8389 8252 7957 7962 7961 8390 7800 7962 7961 7800 8390 8109 8255 7800 8390 8255 8391 8256 8392 8255 8109 8111 8110 8393 7805 8111 8110 7805 8393 7968 8258 7805 8393 8258 8394 8395 8396 8258 7968 7967 8397 8259 8398 7967 7966 8114 8113 8399 7811 8114 8113 7811 8399 8261 7970 8399 7970 7811 8261 8263 7972 8261 7972 7970 8263 8116 8265 7972 8263 8265 8400 8401 8402 8265 8116 8118 8403 8404 8405 8118 8117 8120 8406 8407 8408 8120 8119 8122 8409 8266 8410 8122 8121 8124 8123 8411 7975 8124 8123 7975 8411 8268 7977 8411 7977 7975 8268 8270 7979 8268 7979 7977 8270 8272 7981 8270 7981 7979 8272 8274 7983 8272 7983 7981 8274 8126 8276 7983 8274 8276 8412 8413 8414 8276 8126 8128 8415 8416 8417 8128 8127 8130 8418 8277 8419 8130 8129 8132 8131 8420 7833 8132 8131 7833 8420 8279 7985 8420 7985 7833 8279 7989 8281 7985 8279 8281 8421 8136 8422 8281 7989 7988 7987 8423 8282 7988 7987 8282 8423 8135 7992 8423 7992 8282 8135 8284 8285 7992 8135 8285 8284 8424 8286 8285 8284 8286 8424 7996 8287 8286 8424 8287 8425 8288 8426 8287 7996 7995 7994 8427 7839 7995 7994 7839 8427 8290 8291 7839 8427 8291 8290 8428 7842 8291 8290 7842 8428 8429 8295 7842 8428 8295 8429 8430 8296 8296 8295 8429 8430 8431 8297 8296 8430 8297 8431 7847 8298 8297 8431 8298 7847 8432 8299 8299 8298 7847 8432 8433 8300 8299 8432 8300 8433 7705 8301 8300 8433 8301 7705 8434 8302 8302 8301 7705 8434 8435 8303 8303 8302 8434 8435 8436 8151 8151 8303 8435 8436 8304 8307 8151 8436 8307 229 231 8154 8307 8304 8306 230 8308 231 8306 8305 8154 8437 8438 226 8305 229 8154 230 8438 8437 8155 8308 227 8156 231 8308 227 8308 8437 753 227 228 752 758 8157 759 224 221 755 8311 751 8157 757 750 751 757 755 8439 8309 8311 751 8311 8310 8309 8440 8312 8441 8313 8440 8158 8310 8312 8313 8312 8440 8442 8314 8441 8314 8313 8441 8443 8315 8442 8315 8314 8442 8444 8316 8443 8316 8315 8443 8163 8317 8444 8316 8444 8317 8162 8318 8163 8318 8317 8163 8445 8319 8162 8319 8318 8162 7869 8320 8445 8320 8319 8445 7870 7869 8446 7871 8320 7869 8024 8321 7870 8321 7871 7870 8024 8447 8022 8321 8024 8023 8448 8322 8022 8322 8023 8022 8449 8323 8448 8322 8448 8323 8172 8324 8449 8324 8323 8449 8172 8174 8176 8324 8172 8177 8028 8325 8176 8325 8177 8176 8028 8450 8027 8325 8028 7881 8451 7879 8027 7881 8027 7879 8033 8328 8451 8328 7879 8451 8033 8326 8031 8328 8033 8032 8031 8452 8182 8032 8031 8035 8453 8036 8182 8035 8182 8036 8040 8331 8453 8331 8036 8453 8038 8040 8454 8039 8331 8040 8038 8455 8185 8039 8038 8186 8185 8456 8187 8186 8185 7893 8187 8457 8332 7893 8187 7891 8458 8042 8332 7891 8332 8042 8334 8044 8458 8042 8458 8044 8337 8046 8334 8044 8334 8046 8050 8341 8337 8341 8046 8337 8459 8048 8460 8049 8341 8050 8048 8459 8190 8049 8048 8191 8190 8461 8192 8191 8190 8193 8192 8462 8194 8193 8192 8195 8194 8463 8196 8195 8194 8197 8196 8464 8198 8197 8196 8052 8465 8053 8198 8052 8198 8053 8343 8055 8465 8053 8465 8055 8059 8347 8343 8347 8055 8343 8057 8059 8466 8058 8347 8059 8057 8467 8201 8058 8057 8202 8201 8468 8203 8202 8201 8061 8469 8062 8203 8061 8203 8062 8205 8350 8469 8350 8062 8469 8205 8348 8206 8350 8205 7913 8470 7911 8206 7913 8206 7911 8208 8353 8470 8353 7911 8470 8208 8351 8209 8353 8208 8210 8068 8354 8209 8354 8210 8209 8068 8471 8066 8354 8068 8067 7918 8355 8066 8355 8067 8066 7918 8472 7919 8355 7918 7917 7922 8356 7919 8356 7917 7919 7922 8473 7923 8356 7922 7921 8474 8357 7923 8357 7921 7923 7630 8358 8474 8358 8357 8474 7630 8475 7631 8358 7630 7629 8476 8359 7631 8359 7629 7631 8477 7633 8476 7633 8359 8476 8362 7634 8477 7634 7633 8477 8362 8478 8360 7634 8362 8361 8479 8363 8360 8363 8361 8360 8480 8364 8479 8364 8363 8479 8481 8365 8480 8365 8364 8480 8482 8366 8481 8366 8365 8481 8483 8367 8482 8367 8366 8482 8484 8368 8483 8368 8367 8483 8485 8369 8484 8369 8368 8484 8486 8370 8485 8370 8369 8485 8487 8371 8486 8371 8370 8486 8488 8372 8487 8372 8371 8487 8489 8373 8488 8373 8372 8488 8490 8374 8489 8374 8373 8489 8491 8375 8490 8375 8374 8490 8492 8376 8491 8376 8375 8491 8237 8377 8492 8376 8492 8377 8237 8236 8378 8493 8379 8236 8240 8377 8378 8379 8378 8236 8494 7654 8493 7654 8379 8493 8382 7655 8494 7655 7654 8494 8380 8382 8495 8381 7655 8382 8496 8383 8380 8383 8381 8380 8245 8384 8496 8383 8496 8384 8244 8385 8245 8385 8384 8245 7796 8386 8244 8386 8385 8244 7796 8497 7797 8386 7796 7798 7958 8387 7797 8387 7798 7797 7959 7958 8498 8387 7958 7957 8499 7961 7959 7957 7959 7961 8253 8390 8499 8390 7961 8499 8253 8388 8254 8390 8253 8109 8500 8110 8254 8109 8254 8110 8256 8393 8500 8393 8110 8500 8256 8391 8257 8393 8256 7968 8501 7966 8257 7968 8257 7966 8395 8113 8501 7966 8501 8113 8259 8399 8395 8399 8113 8395 8259 8397 8260 8399 8259 8261 8260 8502 8262 8261 8260 8263 8262 8503 8264 8263 8262 8116 8504 8117 8264 8116 8264 8117 8401 8119 8504 8117 8504 8119 8404 8121 8401 8119 8401 8121 8407 8123 8404 8121 8404 8123 8266 8411 8407 8411 8123 8407 8267 8266 8505 8411 8266 8268 8267 8506 8269 8268 8267 8270 8269 8507 8271 8270 8269 8272 8271 8508 8273 8272 8271 8274 8273 8509 8275 8274 8273 8126 8510 8127 8275 8126 8275 8127 8413 8129 8510 8127 8510 8129 8416 8131 8413 8129 8413 8131 8277 8420 8416 8420 8131 8416 8277 8418 8278 8420 8277 8279 8278 8511 8280 8279 8278 7989 8512 7987 8280 7989 8280 7987 8136 8423 8512 8423 7987 8512 8136 8421 8134 8423 8136 8135 8134 8513 8283 8135 8134 8284 8139 8424 8283 8424 8284 8283 8138 8139 8514 8424 8139 7996 8515 7994 8138 7996 8138 7994 8288 8427 8515 8427 7994 8515 8288 8425 8289 8427 8288 8290 8516 8428 8289 8428 8290 8289 8293 8429 8516 8428 8516 8429 8292 8430 8293 8430 8429 8293 7845 8431 8292 8431 8430 8292 7845 8517 7846 8431 7845 7847 8518 8432 7846 8432 7847 7846 7706 8433 8518 8433 8432 8518 7706 8519 7707 8433 7706 7705 8520 8434 7707 8434 7705 7707 8521 8435 8520 8435 8434 8520 8522 8436 8521 8436 8435 8521 8523 8304 8522 8304 8436 8522 8524 8305 8523 8305 8304 8523 8525 229 8524 229 8305 8524 8438 8525 8526 230 229 8525 230 8525 8438 227 8437 225 8308 230 8437 8437 226 225 228 225 224 224 759 758 223 759 221 754 8527 8311 757 759 755 754 8311 755 8311 8527 8439 8439 8528 8309 8309 8528 8440 8528 8529 8440 8440 8529 8441 8529 8530 8441 8441 8530 8442 8530 8531 8442 8531 8532 8443 8531 8443 8442 8532 8533 8444 8532 8444 8443 8533 8534 8163 8533 8163 8444 8161 8163 8534 8161 8535 8162 8535 8536 8445 8535 8445 8162 8536 8537 7869 8536 7869 8445 8446 7869 8537 8446 8538 7870 8538 8447 8024 8538 8024 7870 8447 8539 8022 8539 8540 8022 8540 8541 8448 8540 8448 8022 8541 8542 8449 8541 8449 8448 8173 8449 8542 8173 8172 8449 8174 8543 8176 8543 8544 8176 8544 8450 8028 8544 8028 8176 8450 8545 8027 8545 8546 8027 8546 8547 8451 8546 8451 8027 8327 8451 8547 8327 8033 8451 8326 8548 8031 8548 8452 8031 8452 8549 8182 8549 8550 8182 8550 8551 8453 8550 8453 8182 8330 8453 8551 8330 8040 8453 8454 8040 8329 8454 8455 8038 8455 8552 8185 8552 8456 8185 8456 8553 8187 8553 8457 8187 8457 8554 8332 8554 8555 8332 8555 8556 8458 8555 8458 8332 8335 8458 8556 8335 8334 8458 8338 8334 8333 8338 8337 8334 8340 8337 8336 8340 8050 8337 8460 8050 8339 8460 8048 8050 8459 8557 8190 8557 8461 8190 8461 8558 8192 8558 8462 8192 8462 8559 8194 8559 8463 8194 8463 8560 8196 8560 8464 8196 8464 8561 8198 8561 8562 8198 8562 8563 8465 8562 8465 8198 8344 8465 8563 8344 8343 8465 8346 8343 8342 8346 8059 8343 8466 8059 8345 8466 8467 8057 8467 8564 8201 8564 8468 8201 8468 8565 8203 8565 8566 8203 8566 8567 8469 8566 8469 8203 8349 8469 8567 8349 8205 8469 8348 8568 8206 8568 8569 8206 8569 8570 8470 8569 8470 8206 8352 8470 8570 8352 8208 8470 8351 8571 8209 8571 8572 8209 8572 8471 8068 8572 8068 8209 8471 8573 8066 8573 8574 8066 8574 8472 7918 8574 7918 8066 8472 8575 7919 8575 8576 7919 8576 8473 7922 8576 7922 7919 8473 8577 7923 8577 8578 7923 8578 8579 8474 8578 8474 7923 8579 8475 7630 8579 7630 8474 8475 8580 7631 8580 8581 7631 7631 8581 8476 8581 8582 8476 8582 8583 8477 8582 8477 8476 8583 8478 8362 8583 8362 8477 8478 8584 8360 8584 8585 8360 8360 8585 8479 8585 8586 8479 8479 8586 8480 8586 8587 8480 8480 8587 8481 8587 8588 8481 8588 8589 8482 8588 8482 8481 8589 8590 8483 8589 8483 8482 8590 8591 8484 8590 8484 8483 8591 8592 8485 8591 8485 8484 8592 8593 8486 8592 8486 8485 8593 8594 8487 8593 8487 8486 8594 8595 8488 8594 8488 8487 8595 8596 8489 8595 8489 8488 8596 8597 8490 8596 8490 8489 8597 8598 8491 8597 8491 8490 8598 8599 8492 8598 8492 8491 8599 8600 8237 8599 8237 8492 8235 8237 8600 8235 8601 8236 8236 8601 8493 8601 8602 8493 8602 8603 8494 8602 8494 8493 8603 8604 8382 8603 8382 8494 8495 8382 8604 8495 8605 8380 8605 8606 8496 8605 8496 8380 8606 8607 8245 8606 8245 8496 8246 8245 8607 8246 8608 8244 8608 8497 7796 8608 7796 8244 8497 8609 7797 8609 8610 7797 8610 8611 7958 8610 7958 7797 7958 8611 8498 8498 8612 7959 8612 8613 8499 8612 8499 7959 8389 8499 8613 8389 8253 8499 8388 8614 8254 8614 8615 8254 8615 8616 8500 8615 8500 8254 8392 8500 8616 8392 8256 8500 8391 8617 8257 8617 8618 8257 8618 8619 8501 8618 8501 8257 8396 8501 8619 8396 8395 8501 8398 8395 8394 8398 8259 8395 8397 8620 8260 8620 8502 8260 8502 8621 8262 8621 8503 8262 8503 8622 8264 8622 8623 8264 8623 8624 8504 8623 8504 8264 8402 8504 8624 8402 8401 8504 8405 8401 8400 8405 8404 8401 8408 8404 8403 8408 8407 8404 8410 8407 8406 8410 8266 8407 8266 8409 8505 8505 8506 8267 8506 8625 8269 8625 8507 8269 8507 8626 8271 8626 8508 8271 8508 8627 8273 8627 8509 8273 8509 8628 8275 8628 8629 8275 8629 8630 8510 8629 8510 8275 8414 8510 8630 8414 8413 8510 8417 8413 8412 8417 8416 8413 8419 8416 8415 8419 8277 8416 8418 8631 8278 8631 8511 8278 8511 8632 8280 8632 8633 8280 8633 8634 8512 8633 8512 8280 8422 8512 8634 8422 8136 8512 8421 8635 8134 8635 8513 8134 8513 8636 8283 8636 8637 8283 8637 8638 8139 8637 8139 8283 8139 8638 8514 8514 8639 8138 8639 8640 8515 8639 8515 8138 8426 8515 8640 8426 8288 8515 8425 8641 8289 8641 8642 8289 8642 8643 8516 8642 8516 8289 8643 8644 8293 8643 8293 8516 8294 8293 8644 8294 8645 8292 8645 8517 7845 8645 7845 8292 8517 8646 7846 8646 8647 7846 8647 8648 8518 8647 8518 7846 8648 8519 7706 8648 7706 8518 8519 8649 7707 8649 8650 7707 7707 8650 8520 8650 8651 8520 8651 8652 8521 8651 8521 8520 8652 8653 8522 8652 8522 8521 8653 8654 8523 8653 8523 8522 8654 8655 8524 8654 8524 8523 8655 8526 8525 8655 8525 8524 8526 8656 8438 8656 8657 8438 8438 8657 226 8657 8658 226 221 224 222 226 8658 222 223 222 8658 8659 8660 8661 8662 8663 8664 8665 8666 8667 8668 8669 8670 8671 8672 8673 8674 8675 8676 8677 8678 8679 8680 8681 8682 8683 8684 8685 8686 8687 8688 8689 8690 8691 8692 8693 8694 8695 8696 8697 8698 8699 8700 8701 8702 8703 8704 8705 8706 8707 8708 8709 8710 8711 8712 8713 8714 8715 8716 8717 8718 8719 8720 8721 8722 8723 8724 8725 8726 8727 8728 8729 8730 8731 8732 8733 8734 8735 8736 8737 8738 8739 8740 8741 8742 8743 8744 8745 8746 8747 8748 8749 8750 8751 8752 8753 8754 8755 8756 8757 8758 8759 8760 8761 8762 8763 8764 8765 8766 8767 8768 8769 8770 8771 8772 8773 8774 8775 8776 8777 8778 8779 8780 8781 8782 8783 8784 8785 8786 8787 8788 8789 8790 8791 8792 8793 8794 8795 8796 8797 8798 8799 8800 8801 8802 8803 8804 8805 8806 8807 8808 8809 8810 8811 8812 8813 8814 8815 8816 8817 8818 8819 8820 8821 8822 8823 8824 8825 8826 8827 8828 8829 8830 8831 8832 8833 8834 8835 8836 8837 8838 8839 8840 8841 8842 8843 8844 8845 8846 8847 8848 8849 8850 8851 8852 8853 8854 8855 8856 8857 8858 8859 8860 8861 8862 8863 8864 8865 8866 8867 8868 8869 8870 8871 8872 8873 8874 8875 8876 8877 8878 8879 8880 8881 8882 8883 8884 8885 8886 8887 8888 8889 8890 8891 8892 8893 8894 8895 8896 8897 8898 8899 8900 8901 8902 8903 8904 8905 8906 8907 8908 8909 8910 8911 8912 8913 8914 8915 8916 8917 8918 8919 8920 8921 8922 8923 8924 8925 8926 8927 8928 8929 8930 8931 8932 8933 8934 8935 8936 8937 8938 8939 8940 8941 8942 8943 8944 8945 8946 8947 8948 8949 8950 8951 8952 8953 8954 8955 8956 8957 8958 8959 8960 8961 8962 8963 8964 8965 8966 8967 8968 8969 8970 8971 8972 8973 8974 8975 8976 8977 8978 8979 8980 8981 8982 8983 8984 8985 8986 8987 8988 8989 8990 8991 8992 8993 8994 8995 8996 8997 8997 8998 8995 8999 9000 8996 8997 8996 9000 9001 8999 9002 8999 9001 9000 9002 9003 9004 9004 9001 9002 9005 9006 9003 9004 9003 9006 9007 9005 9008 9005 9007 9006 9008 9009 9010 9010 9007 9008 9011 9012 9009 9010 9009 9012 9013 9011 9014 9011 9013 9012 9014 9015 9016 9016 9013 9014 9017 9018 9015 9016 9015 9018 9019 9017 9020 9017 9019 9018 9020 9021 9022 9022 9019 9020 9023 9024 9021 9022 9021 9024 9025 9023 9026 9023 9025 9024 9026 9027 9028 9028 9025 9026 9029 9030 9027 9028 9027 9030 9031 9029 9032 9029 9031 9030 9032 9033 9034 9034 9031 9032 9035 9036 9033 9034 9033 9036 9037 9035 9038 9035 9037 9036 9038 9039 9040 9040 9037 9038 9041 9042 9039 9040 9039 9042 9043 9041 9044 9041 9043 9042 9044 9045 9046 9046 9043 9044 9047 9048 9045 9046 9045 9048 9049 9047 9050 9047 9049 9048 9050 9051 9052 9052 9049 9050 9053 9054 9051 9052 9051 9054 9055 9053 9056 9053 9055 9054 9056 9057 9058 9058 9055 9056 9059 9060 9057 9058 9057 9060 9061 9059 9062 9059 9061 9060 9062 9063 9064 9064 9061 9062 9065 9066 9063 9064 9063 9066 9067 9065 9068 9065 9067 9066 9068 9069 9070 9070 9067 9068 9071 9072 9069 9070 9069 9072 9073 9071 9074 9071 9073 9072 9074 9075 9076 9076 9073 9074 9077 9078 9075 9076 9075 9078 9079 9077 9080 9077 9079 9078 9080 9081 9082 9082 9079 9080 9083 9084 9081 9082 9081 9084 9085 9083 9086 9083 9085 9084 9086 9087 9088 9088 9085 9086 9089 9090 9087 9088 9087 9090 9091 9089 9092 9089 9091 9090 9092 9093 9094 9094 9091 9092 9095 9096 9093 9094 9093 9096 9097 9095 9098 9095 9097 9096 9098 9099 9100 9100 9097 9098 9101 9102 9099 9100 9099 9102 9103 9101 9104 9101 9103 9102 9104 9105 9106 9106 9103 9104 8662 8664 9105 9106 9105 8664 8998 8991 8990 8990 8995 8998 8989 8994 8993 8989 8991 8994 8992 8984 8983 8993 8992 8983 8987 8986 8985 8984 8987 8985 8977 8979 8988 8988 8979 8986 8982 8978 8980 8980 8978 8977 8972 8981 8973 8972 8982 8981 8971 8976 8975 8971 8973 8976 8974 8966 8965 8975 8974 8965 8969 8968 8967 8966 8969 8967 8959 8961 8970 8970 8961 8968 8964 8960 8962 8962 8960 8959 8954 8963 8955 8954 8964 8963 8953 8958 8957 8953 8955 8958 8956 8948 8947 8957 8956 8947 8951 8950 8949 8948 8951 8949 8941 8943 8952 8952 8943 8950 8946 8942 8944 8944 8942 8941 8936 8945 8937 8936 8946 8945 8935 8940 8939 8935 8937 8940 8938 8930 8929 8939 8938 8929 8933 8932 8931 8930 8933 8931 8923 8925 8934 8934 8925 8932 8928 8924 8926 8926 8924 8923 8918 8927 8919 8918 8928 8927 8917 8922 8921 8917 8919 8922 8920 8912 8911 8921 8920 8911 8915 8914 8913 8912 8915 8913 8905 8907 8916 8916 8907 8914 8910 8906 8908 8908 8906 8905 8900 8909 8901 8900 8910 8909 8899 8904 8903 8899 8901 8904 8902 8894 8893 8903 8902 8893 8897 8896 8895 8894 8897 8895 8887 8889 8898 8898 8889 8896 8892 8888 8890 8890 8888 8887 8882 8891 8883 8882 8892 8891 8881 8886 8885 8881 8883 8886 8884 8876 8875 8885 8884 8875 8879 8878 8877 8876 8879 8877 8869 8871 8880 8880 8871 8878 8874 8870 8872 8872 8870 8869 8864 8873 8865 8864 8874 8873 8863 8868 8867 8863 8865 8868 8866 8858 8857 8867 8866 8857 8861 8860 8859 8858 8861 8859 8851 8853 8862 8862 8853 8860 8856 8852 8854 8854 8852 8851 8846 8855 8847 8846 8856 8855 8845 8850 8849 8845 8847 8850 8848 8840 8839 8849 8848 8839 8843 8842 8841 8840 8843 8841 8833 8835 8844 8844 8835 8842 8838 8834 8836 8836 8834 8833 8828 8837 8829 8828 8838 8837 8827 8832 8831 8827 8829 8832 8830 8822 8821 8831 8830 8821 8825 8824 8823 8822 8825 8823 8815 8817 8826 8826 8817 8824 8820 8816 8818 8818 8816 8815 8810 8819 8811 8810 8820 8819 8809 8814 8813 8809 8811 8814 8812 8804 8803 8813 8812 8803 8807 8806 8805 8804 8807 8805 8797 8799 8808 8808 8799 8806 8802 8798 8800 8800 8798 8797 8792 8801 8793 8792 8802 8801 8791 8796 8795 8791 8793 8796 8794 8786 8785 8795 8794 8785 8789 8788 8787 8786 8789 8787 8779 8781 8790 8790 8781 8788 8784 8780 8782 8782 8780 8779 8774 8783 8775 8774 8784 8783 8773 8778 8777 8773 8775 8778 8776 8768 8767 8777 8776 8767 8771 8770 8769 8768 8771 8769 8761 8763 8772 8772 8763 8770 8766 8762 8764 8764 8762 8761 8756 8765 8757 8756 8766 8765 8755 8760 8759 8755 8757 8760 8758 8750 8749 8759 8758 8749 8753 8752 8751 8750 8753 8751 8743 8745 8754 8754 8745 8752 8748 8744 8746 8746 8744 8743 8738 8747 8739 8738 8748 8747 8737 8742 8741 8737 8739 8742 8740 8732 8731 8741 8740 8731 8735 8734 8733 8732 8735 8733 8725 8727 8736 8736 8727 8734 8730 8726 8728 8728 8726 8725 8720 8729 8721 8720 8730 8729 8719 8724 8723 8719 8721 8724 8722 8714 8713 8723 8722 8713 8717 8716 8715 8714 8717 8715 8707 8709 8718 8718 8709 8716 8712 8708 8710 8710 8708 8707 8702 8711 8703 8702 8712 8711 8701 8706 8705 8701 8703 8706 8704 8696 8695 8705 8704 8695 8699 8698 8697 8696 8699 8697 8689 8691 8700 8700 8691 8698 8694 8690 8692 8692 8690 8689 8684 8693 8685 8684 8694 8693 8683 8688 8687 8683 8685 8688 8686 8678 8677 8687 8686 8677 8681 8680 8679 8678 8681 8679 8671 8673 8682 8682 8673 8680 8676 8672 8674 8674 8672 8671 8666 8675 8667 8666 8676 8675 8665 8668 8670 8665 8667 8668 8669 8659 8661 8670 8669 8661 8663 8662 8660 8659 8663 8660

-
-
-
-
- - - - - - 1 0 0 0 0 1.17961e-16 1 0 0 -1 1.17961e-16 0 0 0 0 1 - - - - 1 0 0 0 0 -1.17961e-16 -1 0 0 1 -1.17961e-16 0 0 0 0 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/src/tsukuba2022/meshes/right_wheel.dae b/src/tsukuba2022/meshes/right_wheel.dae deleted file mode 100644 index e0ea638..0000000 --- a/src/tsukuba2022/meshes/right_wheel.dae +++ /dev/null @@ -1,174 +0,0 @@ - - - - - 2022-05-02T17:50:01 - 2022-05-02T17:50:01 - - Z_UP - - - - - - - - - - - - - - - - - - 0.913725 0.913725 0.913725 1 - - - 1 1 1 1 - - - 1 - - - - - - 1 - - - - - - - - - - 0.301961 0.301961 0.301961 1 - - - 1 1 1 1 - - - 1 - - - - - - 1 - - - - - - - - - - - 1.60781e-17 0.05 -0.01 1.60781e-17 0.05 0.01 -0.00156793 0.0500822 0.01 0.015 0.065 0.01 0.015 0.065 -0.01 0.0149178 0.0665679 -0.01 -0.00311868 0.0503278 0.01 -0.00156793 0.0500822 -0.01 -0.00463525 0.0507342 0.01 -0.00311868 0.0503278 -0.01 -0.00463525 0.0507342 -0.01 -0.00610105 0.0512968 0.01 -0.0075 0.0520096 0.01 -0.00610105 0.0512968 -0.01 -0.00881678 0.0528647 0.01 -0.0075 0.0520096 -0.01 -0.00881678 0.0528647 -0.01 -0.010037 0.0538528 0.01 -0.0111472 0.054963 0.01 -0.010037 0.0538528 -0.01 -0.0121353 0.0561832 0.01 -0.0111472 0.054963 -0.01 -0.0121353 0.0561832 -0.01 -0.0129904 0.0575 0.01 -0.0137032 0.0588989 0.01 -0.0129904 0.0575 -0.01 -0.0142658 0.0603647 0.01 -0.0137032 0.0588989 -0.01 -0.0142658 0.0603647 -0.01 -0.0146722 0.0618813 0.01 -0.0149178 0.0634321 0.01 -0.0146722 0.0618813 -0.01 -0.015 0.065 0.01 -0.0149178 0.0634321 -0.01 -0.015 0.065 -0.01 0.00156793 0.0500822 -0.01 0.00311868 0.0503278 -0.01 0.00156793 0.0500822 0.01 0.00311868 0.0503278 0.01 0.00463525 0.0507342 -0.01 0.00610105 0.0512968 -0.01 0.00463525 0.0507342 0.01 0.0075 0.0520096 -0.01 0.00610105 0.0512968 0.01 0.0075 0.0520096 0.01 0.00881678 0.0528647 -0.01 0.010037 0.0538528 -0.01 0.00881678 0.0528647 0.01 0.0111472 0.054963 -0.01 0.010037 0.0538528 0.01 0.0111472 0.054963 0.01 0.0121353 0.0561832 -0.01 0.0129904 0.0575 -0.01 0.0121353 0.0561832 0.01 0.0137032 0.0588989 -0.01 0.0129904 0.0575 0.01 0.0137032 0.0588989 0.01 0.0142658 0.0603647 -0.01 0.0146722 0.0618813 -0.01 0.0142658 0.0603647 0.01 0.0149178 0.0634321 -0.01 0.0146722 0.0618813 0.01 0.0149178 0.0634321 0.01 0.0146722 0.0681187 0.01 0.0149178 0.0665679 0.01 0.0146722 0.0681187 -0.01 0.0129904 0.0725 0.01 0.0137032 0.0711011 0.01 0.0129904 0.0725 -0.01 0.0142658 0.0696353 0.01 0.0142658 0.0696353 -0.01 0.0137032 0.0711011 -0.01 0.0111472 0.075037 0.01 0.010037 0.0761472 -0.01 0.010037 0.0761472 0.01 0.0121353 0.0738168 -0.01 0.0111472 0.075037 -0.01 0.0121353 0.0738168 0.01 0.00610105 0.0787032 -0.01 0.00610105 0.0787032 0.01 0.0075 0.0779904 0.01 0.0075 0.0779904 -0.01 0.00881678 0.0771353 0.01 0.00881678 0.0771353 -0.01 0.00156793 0.0799178 0.01 0.00311868 0.0796722 0.01 0.00156793 0.0799178 -0.01 0.00463525 0.0792658 0.01 0.00463525 0.0792658 -0.01 0.00311868 0.0796722 -0.01 -0.00156793 0.0799178 0.01 -0.00311868 0.0796722 -0.01 -0.00311868 0.0796722 0.01 -4.24915e-18 0.08 -0.01 -0.00156793 0.0799178 -0.01 -4.24915e-18 0.08 0.01 -0.0075 0.0779904 -0.01 -0.0075 0.0779904 0.01 -0.00610105 0.0787032 0.01 -0.00610105 0.0787032 -0.01 -0.00463525 0.0792658 0.01 -0.00463525 0.0792658 -0.01 -0.0111472 0.075037 0.01 -0.010037 0.0761472 0.01 -0.0111472 0.075037 -0.01 -0.00881678 0.0771353 0.01 -0.00881678 0.0771353 -0.01 -0.010037 0.0761472 -0.01 -0.0121353 0.0738168 -0.01 -0.0121353 0.0738168 0.01 -0.0129904 0.0725 -0.01 -0.0129904 0.0725 0.01 -0.0137032 0.0711011 0.01 -0.0137032 0.0711011 -0.01 -0.0142658 0.0696353 -0.01 -0.0142658 0.0696353 0.01 -0.0146722 0.0681187 -0.01 -0.0146722 0.0681187 0.01 -0.0149178 0.0665679 0.01 -0.0149178 0.0665679 -0.01 0.0459619 0.0309619 -0.01 0.0459619 0.0309619 0.01 0.044394 0.0310441 0.01 0.0609619 0.0459619 0.01 0.0609619 0.0459619 -0.01 0.0608798 0.0475299 -0.01 0.0428433 0.0312897 0.01 0.044394 0.0310441 -0.01 0.0413267 0.0316961 0.01 0.0428433 0.0312897 -0.01 0.0413267 0.0316961 -0.01 0.0398609 0.0322588 0.01 0.0384619 0.0329716 0.01 0.0398609 0.0322588 -0.01 0.0371452 0.0338267 0.01 0.0384619 0.0329716 -0.01 0.0371452 0.0338267 -0.01 0.035925 0.0348148 0.01 0.0348148 0.035925 0.01 0.035925 0.0348148 -0.01 0.0338267 0.0371452 0.01 0.0348148 0.035925 -0.01 0.0338267 0.0371452 -0.01 0.0329716 0.0384619 0.01 0.0322588 0.0398609 0.01 0.0329716 0.0384619 -0.01 0.0316961 0.0413267 0.01 0.0322588 0.0398609 -0.01 0.0316961 0.0413267 -0.01 0.0312897 0.0428433 0.01 0.0310441 0.044394 0.01 0.0312897 0.0428433 -0.01 0.0309619 0.0459619 0.01 0.0310441 0.044394 -0.01 0.0309619 0.0459619 -0.01 0.0475299 0.0310441 -0.01 0.0490806 0.0312897 -0.01 0.0475299 0.0310441 0.01 0.0490806 0.0312897 0.01 0.0505972 0.0316961 -0.01 0.052063 0.0322588 -0.01 0.0505972 0.0316961 0.01 0.0534619 0.0329716 -0.01 0.052063 0.0322588 0.01 0.0534619 0.0329716 0.01 0.0547787 0.0338267 -0.01 0.0559989 0.0348148 -0.01 0.0547787 0.0338267 0.01 0.0571091 0.035925 -0.01 0.0559989 0.0348148 0.01 0.0571091 0.035925 0.01 0.0580972 0.0371452 -0.01 0.0589523 0.0384619 -0.01 0.0580972 0.0371452 0.01 0.0596651 0.0398609 -0.01 0.0589523 0.0384619 0.01 0.0596651 0.0398609 0.01 0.0602278 0.0413267 -0.01 0.0606342 0.0428433 -0.01 0.0602278 0.0413267 0.01 0.0608798 0.044394 -0.01 0.0606342 0.0428433 0.01 0.0608798 0.044394 0.01 0.0606342 0.0490806 0.01 0.0608798 0.0475299 0.01 0.0606342 0.0490806 -0.01 0.0589523 0.0534619 0.01 0.0596651 0.052063 0.01 0.0589523 0.0534619 -0.01 0.0602278 0.0505972 0.01 0.0602278 0.0505972 -0.01 0.0596651 0.052063 -0.01 0.0571091 0.0559989 0.01 0.0559989 0.0571091 -0.01 0.0559989 0.0571091 0.01 0.0580972 0.0547787 -0.01 0.0571091 0.0559989 -0.01 0.0580972 0.0547787 0.01 0.052063 0.0596651 -0.01 0.052063 0.0596651 0.01 0.0534619 0.0589523 0.01 0.0534619 0.0589523 -0.01 0.0547787 0.0580972 0.01 0.0547787 0.0580972 -0.01 0.0475299 0.0608798 0.01 0.0490806 0.0606342 0.01 0.0475299 0.0608798 -0.01 0.0505972 0.0602278 0.01 0.0505972 0.0602278 -0.01 0.0490806 0.0606342 -0.01 0.044394 0.0608798 0.01 0.0428433 0.0606342 -0.01 0.0428433 0.0606342 0.01 0.0459619 0.0609619 -0.01 0.044394 0.0608798 -0.01 0.0459619 0.0609619 0.01 0.0384619 0.0589523 -0.01 0.0384619 0.0589523 0.01 0.0398609 0.0596651 0.01 0.0398609 0.0596651 -0.01 0.0413267 0.0602278 0.01 0.0413267 0.0602278 -0.01 0.0348148 0.0559989 0.01 0.035925 0.0571091 0.01 0.0348148 0.0559989 -0.01 0.0371452 0.0580972 0.01 0.0371452 0.0580972 -0.01 0.035925 0.0571091 -0.01 0.0338267 0.0547787 -0.01 0.0338267 0.0547787 0.01 0.0329716 0.0534619 -0.01 0.0329716 0.0534619 0.01 0.0322588 0.052063 0.01 0.0322588 0.052063 -0.01 0.0316961 0.0505972 -0.01 0.0316961 0.0505972 0.01 0.0312897 0.0490806 -0.01 0.0312897 0.0490806 0.01 0.0310441 0.0475299 0.01 0.0310441 0.0475299 -0.01 0.065 -0.015 -0.01 0.065 -0.015 0.01 0.0634321 -0.0149178 0.01 0.08 9.41679e-18 0.01 0.08 9.41679e-18 -0.01 0.0799178 0.00156793 -0.01 0.0618813 -0.0146722 0.01 0.0634321 -0.0149178 -0.01 0.0603647 -0.0142658 0.01 0.0618813 -0.0146722 -0.01 0.0603647 -0.0142658 -0.01 0.0588989 -0.0137032 0.01 0.0575 -0.0129904 0.01 0.0588989 -0.0137032 -0.01 0.0561832 -0.0121353 0.01 0.0575 -0.0129904 -0.01 0.0561832 -0.0121353 -0.01 0.054963 -0.0111472 0.01 0.0538528 -0.010037 0.01 0.054963 -0.0111472 -0.01 0.0528647 -0.00881678 0.01 0.0538528 -0.010037 -0.01 0.0528647 -0.00881678 -0.01 0.0520096 -0.0075 0.01 0.0512968 -0.00610105 0.01 0.0520096 -0.0075 -0.01 0.0507342 -0.00463525 0.01 0.0512968 -0.00610105 -0.01 0.0507342 -0.00463525 -0.01 0.0503278 -0.00311868 0.01 0.0500822 -0.00156793 0.01 0.0503278 -0.00311868 -0.01 0.05 -1.60781e-17 0.01 0.0500822 -0.00156793 -0.01 0.05 -1.60781e-17 -0.01 0.0665679 -0.0149178 -0.01 0.0681187 -0.0146722 -0.01 0.0665679 -0.0149178 0.01 0.0681187 -0.0146722 0.01 0.0696353 -0.0142658 -0.01 0.0711011 -0.0137032 -0.01 0.0696353 -0.0142658 0.01 0.0725 -0.0129904 -0.01 0.0711011 -0.0137032 0.01 0.0725 -0.0129904 0.01 0.0738168 -0.0121353 -0.01 0.075037 -0.0111472 -0.01 0.0738168 -0.0121353 0.01 0.0761472 -0.010037 -0.01 0.075037 -0.0111472 0.01 0.0761472 -0.010037 0.01 0.0771353 -0.00881678 -0.01 0.0779904 -0.0075 -0.01 0.0771353 -0.00881678 0.01 0.0787032 -0.00610105 -0.01 0.0779904 -0.0075 0.01 0.0787032 -0.00610105 0.01 0.0792658 -0.00463525 -0.01 0.0796722 -0.00311868 -0.01 0.0792658 -0.00463525 0.01 0.0799178 -0.00156793 -0.01 0.0796722 -0.00311868 0.01 0.0799178 -0.00156793 0.01 0.0796722 0.00311868 0.01 0.0799178 0.00156793 0.01 0.0796722 0.00311868 -0.01 0.0779904 0.0075 0.01 0.0787032 0.00610105 0.01 0.0779904 0.0075 -0.01 0.0792658 0.00463525 0.01 0.0792658 0.00463525 -0.01 0.0787032 0.00610105 -0.01 0.0761472 0.010037 0.01 0.075037 0.0111472 -0.01 0.075037 0.0111472 0.01 0.0771353 0.00881678 -0.01 0.0761472 0.010037 -0.01 0.0771353 0.00881678 0.01 0.0711011 0.0137032 -0.01 0.0711011 0.0137032 0.01 0.0725 0.0129904 0.01 0.0725 0.0129904 -0.01 0.0738168 0.0121353 0.01 0.0738168 0.0121353 -0.01 0.0665679 0.0149178 0.01 0.0681187 0.0146722 0.01 0.0665679 0.0149178 -0.01 0.0696353 0.0142658 0.01 0.0696353 0.0142658 -0.01 0.0681187 0.0146722 -0.01 0.0634321 0.0149178 0.01 0.0618813 0.0146722 -0.01 0.0618813 0.0146722 0.01 0.065 0.015 -0.01 0.0634321 0.0149178 -0.01 0.065 0.015 0.01 0.0575 0.0129904 -0.01 0.0575 0.0129904 0.01 0.0588989 0.0137032 0.01 0.0588989 0.0137032 -0.01 0.0603647 0.0142658 0.01 0.0603647 0.0142658 -0.01 0.0538528 0.010037 0.01 0.054963 0.0111472 0.01 0.0538528 0.010037 -0.01 0.0561832 0.0121353 0.01 0.0561832 0.0121353 -0.01 0.054963 0.0111472 -0.01 0.0528647 0.00881678 -0.01 0.0528647 0.00881678 0.01 0.0520096 0.0075 -0.01 0.0520096 0.0075 0.01 0.0512968 0.00610105 0.01 0.0512968 0.00610105 -0.01 0.0507342 0.00463525 -0.01 0.0507342 0.00463525 0.01 0.0503278 0.00311868 -0.01 0.0503278 0.00311868 0.01 0.0500822 0.00156793 0.01 0.0500822 0.00156793 -0.01 0.0459619 -0.0609619 -0.01 0.0459619 -0.0609619 0.01 0.044394 -0.0608798 0.01 0.0609619 -0.0459619 0.01 0.0609619 -0.0459619 -0.01 0.0608798 -0.044394 -0.01 0.0428433 -0.0606342 0.01 0.044394 -0.0608798 -0.01 0.0413267 -0.0602278 0.01 0.0428433 -0.0606342 -0.01 0.0413267 -0.0602278 -0.01 0.0398609 -0.0596651 0.01 0.0384619 -0.0589523 0.01 0.0398609 -0.0596651 -0.01 0.0371452 -0.0580972 0.01 0.0384619 -0.0589523 -0.01 0.0371452 -0.0580972 -0.01 0.035925 -0.0571091 0.01 0.0348148 -0.0559989 0.01 0.035925 -0.0571091 -0.01 0.0338267 -0.0547787 0.01 0.0348148 -0.0559989 -0.01 0.0338267 -0.0547787 -0.01 0.0329716 -0.0534619 0.01 0.0322588 -0.052063 0.01 0.0329716 -0.0534619 -0.01 0.0316961 -0.0505972 0.01 0.0322588 -0.052063 -0.01 0.0316961 -0.0505972 -0.01 0.0312897 -0.0490806 0.01 0.0310441 -0.0475299 0.01 0.0312897 -0.0490806 -0.01 0.0309619 -0.0459619 0.01 0.0310441 -0.0475299 -0.01 0.0309619 -0.0459619 -0.01 0.0475299 -0.0608798 -0.01 0.0490806 -0.0606342 -0.01 0.0475299 -0.0608798 0.01 0.0490806 -0.0606342 0.01 0.0505972 -0.0602278 -0.01 0.052063 -0.0596651 -0.01 0.0505972 -0.0602278 0.01 0.0534619 -0.0589523 -0.01 0.052063 -0.0596651 0.01 0.0534619 -0.0589523 0.01 0.0547787 -0.0580972 -0.01 0.0559989 -0.0571091 -0.01 0.0547787 -0.0580972 0.01 0.0571091 -0.0559989 -0.01 0.0559989 -0.0571091 0.01 0.0571091 -0.0559989 0.01 0.0580972 -0.0547787 -0.01 0.0589523 -0.0534619 -0.01 0.0580972 -0.0547787 0.01 0.0596651 -0.052063 -0.01 0.0589523 -0.0534619 0.01 0.0596651 -0.052063 0.01 0.0602278 -0.0505972 -0.01 0.0606342 -0.0490806 -0.01 0.0602278 -0.0505972 0.01 0.0608798 -0.0475299 -0.01 0.0606342 -0.0490806 0.01 0.0608798 -0.0475299 0.01 0.0606342 -0.0428433 0.01 0.0608798 -0.044394 0.01 0.0606342 -0.0428433 -0.01 0.0589523 -0.0384619 0.01 0.0596651 -0.0398609 0.01 0.0589523 -0.0384619 -0.01 0.0602278 -0.0413267 0.01 0.0602278 -0.0413267 -0.01 0.0596651 -0.0398609 -0.01 0.0571091 -0.035925 0.01 0.0559989 -0.0348148 -0.01 0.0559989 -0.0348148 0.01 0.0580972 -0.0371452 -0.01 0.0571091 -0.035925 -0.01 0.0580972 -0.0371452 0.01 0.052063 -0.0322588 -0.01 0.052063 -0.0322588 0.01 0.0534619 -0.0329716 0.01 0.0534619 -0.0329716 -0.01 0.0547787 -0.0338267 0.01 0.0547787 -0.0338267 -0.01 0.0475299 -0.0310441 0.01 0.0490806 -0.0312897 0.01 0.0475299 -0.0310441 -0.01 0.0505972 -0.0316961 0.01 0.0505972 -0.0316961 -0.01 0.0490806 -0.0312897 -0.01 0.044394 -0.0310441 0.01 0.0428433 -0.0312897 -0.01 0.0428433 -0.0312897 0.01 0.0459619 -0.0309619 -0.01 0.044394 -0.0310441 -0.01 0.0459619 -0.0309619 0.01 0.0384619 -0.0329716 -0.01 0.0384619 -0.0329716 0.01 0.0398609 -0.0322588 0.01 0.0398609 -0.0322588 -0.01 0.0413267 -0.0316961 0.01 0.0413267 -0.0316961 -0.01 0.0348148 -0.035925 0.01 0.035925 -0.0348148 0.01 0.0348148 -0.035925 -0.01 0.0371452 -0.0338267 0.01 0.0371452 -0.0338267 -0.01 0.035925 -0.0348148 -0.01 0.0338267 -0.0371452 -0.01 0.0338267 -0.0371452 0.01 0.0329716 -0.0384619 -0.01 0.0329716 -0.0384619 0.01 0.0322588 -0.0398609 0.01 0.0322588 -0.0398609 -0.01 0.0316961 -0.0413267 -0.01 0.0316961 -0.0413267 0.01 0.0312897 -0.0428433 -0.01 0.0312897 -0.0428433 0.01 0.0310441 -0.044394 0.01 0.0310441 -0.044394 -0.01 1.60781e-17 -0.08 -0.01 1.60781e-17 -0.08 0.01 -0.00156793 -0.0799178 0.01 0.015 -0.065 0.01 0.015 -0.065 -0.01 0.0149178 -0.0634321 -0.01 -0.00311868 -0.0796722 0.01 -0.00156793 -0.0799178 -0.01 -0.00463525 -0.0792658 0.01 -0.00311868 -0.0796722 -0.01 -0.00463525 -0.0792658 -0.01 -0.00610105 -0.0787032 0.01 -0.0075 -0.0779904 0.01 -0.00610105 -0.0787032 -0.01 -0.00881678 -0.0771353 0.01 -0.0075 -0.0779904 -0.01 -0.00881678 -0.0771353 -0.01 -0.010037 -0.0761472 0.01 -0.0111472 -0.075037 0.01 -0.010037 -0.0761472 -0.01 -0.0121353 -0.0738168 0.01 -0.0111472 -0.075037 -0.01 -0.0121353 -0.0738168 -0.01 -0.0129904 -0.0725 0.01 -0.0137032 -0.0711011 0.01 -0.0129904 -0.0725 -0.01 -0.0142658 -0.0696353 0.01 -0.0137032 -0.0711011 -0.01 -0.0142658 -0.0696353 -0.01 -0.0146722 -0.0681187 0.01 -0.0149178 -0.0665679 0.01 -0.0146722 -0.0681187 -0.01 -0.015 -0.065 0.01 -0.0149178 -0.0665679 -0.01 -0.015 -0.065 -0.01 0.00156793 -0.0799178 -0.01 0.00311868 -0.0796722 -0.01 0.00156793 -0.0799178 0.01 0.00311868 -0.0796722 0.01 0.00463525 -0.0792658 -0.01 0.00610105 -0.0787032 -0.01 0.00463525 -0.0792658 0.01 0.0075 -0.0779904 -0.01 0.00610105 -0.0787032 0.01 0.0075 -0.0779904 0.01 0.00881678 -0.0771353 -0.01 0.010037 -0.0761472 -0.01 0.00881678 -0.0771353 0.01 0.0111472 -0.075037 -0.01 0.010037 -0.0761472 0.01 0.0111472 -0.075037 0.01 0.0121353 -0.0738168 -0.01 0.0129904 -0.0725 -0.01 0.0121353 -0.0738168 0.01 0.0137032 -0.0711011 -0.01 0.0129904 -0.0725 0.01 0.0137032 -0.0711011 0.01 0.0142658 -0.0696353 -0.01 0.0146722 -0.0681187 -0.01 0.0142658 -0.0696353 0.01 0.0149178 -0.0665679 -0.01 0.0146722 -0.0681187 0.01 0.0149178 -0.0665679 0.01 0.0146722 -0.0618813 0.01 0.0149178 -0.0634321 0.01 0.0146722 -0.0618813 -0.01 0.0129904 -0.0575 0.01 0.0137032 -0.0588989 0.01 0.0129904 -0.0575 -0.01 0.0142658 -0.0603647 0.01 0.0142658 -0.0603647 -0.01 0.0137032 -0.0588989 -0.01 0.0111472 -0.054963 0.01 0.010037 -0.0538528 -0.01 0.010037 -0.0538528 0.01 0.0121353 -0.0561832 -0.01 0.0111472 -0.054963 -0.01 0.0121353 -0.0561832 0.01 0.00610105 -0.0512968 -0.01 0.00610105 -0.0512968 0.01 0.0075 -0.0520096 0.01 0.0075 -0.0520096 -0.01 0.00881678 -0.0528647 0.01 0.00881678 -0.0528647 -0.01 0.00156793 -0.0500822 0.01 0.00311868 -0.0503278 0.01 0.00156793 -0.0500822 -0.01 0.00463525 -0.0507342 0.01 0.00463525 -0.0507342 -0.01 0.00311868 -0.0503278 -0.01 -0.00156793 -0.0500822 0.01 -0.00311868 -0.0503278 -0.01 -0.00311868 -0.0503278 0.01 -4.24915e-18 -0.05 -0.01 -0.00156793 -0.0500822 -0.01 -4.24915e-18 -0.05 0.01 -0.0075 -0.0520096 -0.01 -0.0075 -0.0520096 0.01 -0.00610105 -0.0512968 0.01 -0.00610105 -0.0512968 -0.01 -0.00463525 -0.0507342 0.01 -0.00463525 -0.0507342 -0.01 -0.0111472 -0.054963 0.01 -0.010037 -0.0538528 0.01 -0.0111472 -0.054963 -0.01 -0.00881678 -0.0528647 0.01 -0.00881678 -0.0528647 -0.01 -0.010037 -0.0538528 -0.01 -0.0121353 -0.0561832 -0.01 -0.0121353 -0.0561832 0.01 -0.0129904 -0.0575 -0.01 -0.0129904 -0.0575 0.01 -0.0137032 -0.0588989 0.01 -0.0137032 -0.0588989 -0.01 -0.0142658 -0.0603647 -0.01 -0.0142658 -0.0603647 0.01 -0.0146722 -0.0618813 -0.01 -0.0146722 -0.0618813 0.01 -0.0149178 -0.0634321 0.01 -0.0149178 -0.0634321 -0.01 -0.0459619 -0.0609619 -0.01 -0.0459619 -0.0609619 0.01 -0.0475299 -0.0608798 0.01 -0.0309619 -0.0459619 0.01 -0.0309619 -0.0459619 -0.01 -0.0310441 -0.044394 -0.01 -0.0490806 -0.0606342 0.01 -0.0475299 -0.0608798 -0.01 -0.0505972 -0.0602278 0.01 -0.0490806 -0.0606342 -0.01 -0.0505972 -0.0602278 -0.01 -0.052063 -0.0596651 0.01 -0.0534619 -0.0589523 0.01 -0.052063 -0.0596651 -0.01 -0.0547787 -0.0580972 0.01 -0.0534619 -0.0589523 -0.01 -0.0547787 -0.0580972 -0.01 -0.0559989 -0.0571091 0.01 -0.0571091 -0.0559989 0.01 -0.0559989 -0.0571091 -0.01 -0.0580972 -0.0547787 0.01 -0.0571091 -0.0559989 -0.01 -0.0580972 -0.0547787 -0.01 -0.0589523 -0.0534619 0.01 -0.0596651 -0.052063 0.01 -0.0589523 -0.0534619 -0.01 -0.0602278 -0.0505972 0.01 -0.0596651 -0.052063 -0.01 -0.0602278 -0.0505972 -0.01 -0.0606342 -0.0490806 0.01 -0.0608798 -0.0475299 0.01 -0.0606342 -0.0490806 -0.01 -0.0609619 -0.0459619 0.01 -0.0608798 -0.0475299 -0.01 -0.0609619 -0.0459619 -0.01 -0.044394 -0.0608798 -0.01 -0.0428433 -0.0606342 -0.01 -0.044394 -0.0608798 0.01 -0.0428433 -0.0606342 0.01 -0.0413267 -0.0602278 -0.01 -0.0398609 -0.0596651 -0.01 -0.0413267 -0.0602278 0.01 -0.0384619 -0.0589523 -0.01 -0.0398609 -0.0596651 0.01 -0.0384619 -0.0589523 0.01 -0.0371452 -0.0580972 -0.01 -0.035925 -0.0571091 -0.01 -0.0371452 -0.0580972 0.01 -0.0348148 -0.0559989 -0.01 -0.035925 -0.0571091 0.01 -0.0348148 -0.0559989 0.01 -0.0338267 -0.0547787 -0.01 -0.0329716 -0.0534619 -0.01 -0.0338267 -0.0547787 0.01 -0.0322588 -0.052063 -0.01 -0.0329716 -0.0534619 0.01 -0.0322588 -0.052063 0.01 -0.0316961 -0.0505972 -0.01 -0.0312897 -0.0490806 -0.01 -0.0316961 -0.0505972 0.01 -0.0310441 -0.0475299 -0.01 -0.0312897 -0.0490806 0.01 -0.0310441 -0.0475299 0.01 -0.0312897 -0.0428433 0.01 -0.0310441 -0.044394 0.01 -0.0312897 -0.0428433 -0.01 -0.0329716 -0.0384619 0.01 -0.0322588 -0.0398609 0.01 -0.0329716 -0.0384619 -0.01 -0.0316961 -0.0413267 0.01 -0.0316961 -0.0413267 -0.01 -0.0322588 -0.0398609 -0.01 -0.0348148 -0.035925 0.01 -0.035925 -0.0348148 -0.01 -0.035925 -0.0348148 0.01 -0.0338267 -0.0371452 -0.01 -0.0348148 -0.035925 -0.01 -0.0338267 -0.0371452 0.01 -0.0398609 -0.0322588 -0.01 -0.0398609 -0.0322588 0.01 -0.0384619 -0.0329716 0.01 -0.0384619 -0.0329716 -0.01 -0.0371452 -0.0338267 0.01 -0.0371452 -0.0338267 -0.01 -0.044394 -0.0310441 0.01 -0.0428433 -0.0312897 0.01 -0.044394 -0.0310441 -0.01 -0.0413267 -0.0316961 0.01 -0.0413267 -0.0316961 -0.01 -0.0428433 -0.0312897 -0.01 -0.0475299 -0.0310441 0.01 -0.0490806 -0.0312897 -0.01 -0.0490806 -0.0312897 0.01 -0.0459619 -0.0309619 -0.01 -0.0475299 -0.0310441 -0.01 -0.0459619 -0.0309619 0.01 -0.0534619 -0.0329716 -0.01 -0.0534619 -0.0329716 0.01 -0.052063 -0.0322588 0.01 -0.052063 -0.0322588 -0.01 -0.0505972 -0.0316961 0.01 -0.0505972 -0.0316961 -0.01 -0.0571091 -0.035925 0.01 -0.0559989 -0.0348148 0.01 -0.0571091 -0.035925 -0.01 -0.0547787 -0.0338267 0.01 -0.0547787 -0.0338267 -0.01 -0.0559989 -0.0348148 -0.01 -0.0580972 -0.0371452 -0.01 -0.0580972 -0.0371452 0.01 -0.0589523 -0.0384619 -0.01 -0.0589523 -0.0384619 0.01 -0.0596651 -0.0398609 0.01 -0.0596651 -0.0398609 -0.01 -0.0602278 -0.0413267 -0.01 -0.0602278 -0.0413267 0.01 -0.0606342 -0.0428433 -0.01 -0.0606342 -0.0428433 0.01 -0.0608798 -0.044394 0.01 -0.0608798 -0.044394 -0.01 -0.065 -0.015 -0.01 -0.065 -0.015 0.01 -0.0665679 -0.0149178 0.01 -0.05 9.41679e-18 0.01 -0.05 9.41679e-18 -0.01 -0.0500822 0.00156793 -0.01 -0.0681187 -0.0146722 0.01 -0.0665679 -0.0149178 -0.01 -0.0696353 -0.0142658 0.01 -0.0681187 -0.0146722 -0.01 -0.0696353 -0.0142658 -0.01 -0.0711011 -0.0137032 0.01 -0.0725 -0.0129904 0.01 -0.0711011 -0.0137032 -0.01 -0.0738168 -0.0121353 0.01 -0.0725 -0.0129904 -0.01 -0.0738168 -0.0121353 -0.01 -0.075037 -0.0111472 0.01 -0.0761472 -0.010037 0.01 -0.075037 -0.0111472 -0.01 -0.0771353 -0.00881678 0.01 -0.0761472 -0.010037 -0.01 -0.0771353 -0.00881678 -0.01 -0.0779904 -0.0075 0.01 -0.0787032 -0.00610105 0.01 -0.0779904 -0.0075 -0.01 -0.0792658 -0.00463525 0.01 -0.0787032 -0.00610105 -0.01 -0.0792658 -0.00463525 -0.01 -0.0796722 -0.00311868 0.01 -0.0799178 -0.00156793 0.01 -0.0796722 -0.00311868 -0.01 -0.08 -1.60781e-17 0.01 -0.0799178 -0.00156793 -0.01 -0.08 -1.60781e-17 -0.01 -0.0634321 -0.0149178 -0.01 -0.0618813 -0.0146722 -0.01 -0.0634321 -0.0149178 0.01 -0.0618813 -0.0146722 0.01 -0.0603647 -0.0142658 -0.01 -0.0588989 -0.0137032 -0.01 -0.0603647 -0.0142658 0.01 -0.0575 -0.0129904 -0.01 -0.0588989 -0.0137032 0.01 -0.0575 -0.0129904 0.01 -0.0561832 -0.0121353 -0.01 -0.054963 -0.0111472 -0.01 -0.0561832 -0.0121353 0.01 -0.0538528 -0.010037 -0.01 -0.054963 -0.0111472 0.01 -0.0538528 -0.010037 0.01 -0.0528647 -0.00881678 -0.01 -0.0520096 -0.0075 -0.01 -0.0528647 -0.00881678 0.01 -0.0512968 -0.00610105 -0.01 -0.0520096 -0.0075 0.01 -0.0512968 -0.00610105 0.01 -0.0507342 -0.00463525 -0.01 -0.0503278 -0.00311868 -0.01 -0.0507342 -0.00463525 0.01 -0.0500822 -0.00156793 -0.01 -0.0503278 -0.00311868 0.01 -0.0500822 -0.00156793 0.01 -0.0503278 0.00311868 0.01 -0.0500822 0.00156793 0.01 -0.0503278 0.00311868 -0.01 -0.0520096 0.0075 0.01 -0.0512968 0.00610105 0.01 -0.0520096 0.0075 -0.01 -0.0507342 0.00463525 0.01 -0.0507342 0.00463525 -0.01 -0.0512968 0.00610105 -0.01 -0.0538528 0.010037 0.01 -0.054963 0.0111472 -0.01 -0.054963 0.0111472 0.01 -0.0528647 0.00881678 -0.01 -0.0538528 0.010037 -0.01 -0.0528647 0.00881678 0.01 -0.0588989 0.0137032 -0.01 -0.0588989 0.0137032 0.01 -0.0575 0.0129904 0.01 -0.0575 0.0129904 -0.01 -0.0561832 0.0121353 0.01 -0.0561832 0.0121353 -0.01 -0.0634321 0.0149178 0.01 -0.0618813 0.0146722 0.01 -0.0634321 0.0149178 -0.01 -0.0603647 0.0142658 0.01 -0.0603647 0.0142658 -0.01 -0.0618813 0.0146722 -0.01 -0.0665679 0.0149178 0.01 -0.0681187 0.0146722 -0.01 -0.0681187 0.0146722 0.01 -0.065 0.015 -0.01 -0.0665679 0.0149178 -0.01 -0.065 0.015 0.01 -0.0725 0.0129904 -0.01 -0.0725 0.0129904 0.01 -0.0711011 0.0137032 0.01 -0.0711011 0.0137032 -0.01 -0.0696353 0.0142658 0.01 -0.0696353 0.0142658 -0.01 -0.0761472 0.010037 0.01 -0.075037 0.0111472 0.01 -0.0761472 0.010037 -0.01 -0.0738168 0.0121353 0.01 -0.0738168 0.0121353 -0.01 -0.075037 0.0111472 -0.01 -0.0771353 0.00881678 -0.01 -0.0771353 0.00881678 0.01 -0.0779904 0.0075 -0.01 -0.0779904 0.0075 0.01 -0.0787032 0.00610105 0.01 -0.0787032 0.00610105 -0.01 -0.0792658 0.00463525 -0.01 -0.0792658 0.00463525 0.01 -0.0796722 0.00311868 -0.01 -0.0796722 0.00311868 0.01 -0.0799178 0.00156793 0.01 -0.0799178 0.00156793 -0.01 -0.0459619 0.0309619 -0.01 -0.0459619 0.0309619 0.01 -0.0475299 0.0310441 0.01 -0.0309619 0.0459619 0.01 -0.0309619 0.0459619 -0.01 -0.0310441 0.0475299 -0.01 -0.0490806 0.0312897 0.01 -0.0475299 0.0310441 -0.01 -0.0505972 0.0316961 0.01 -0.0490806 0.0312897 -0.01 -0.0505972 0.0316961 -0.01 -0.052063 0.0322588 0.01 -0.0534619 0.0329716 0.01 -0.052063 0.0322588 -0.01 -0.0547787 0.0338267 0.01 -0.0534619 0.0329716 -0.01 -0.0547787 0.0338267 -0.01 -0.0559989 0.0348148 0.01 -0.0571091 0.035925 0.01 -0.0559989 0.0348148 -0.01 -0.0580972 0.0371452 0.01 -0.0571091 0.035925 -0.01 -0.0580972 0.0371452 -0.01 -0.0589523 0.0384619 0.01 -0.0596651 0.0398609 0.01 -0.0589523 0.0384619 -0.01 -0.0602278 0.0413267 0.01 -0.0596651 0.0398609 -0.01 -0.0602278 0.0413267 -0.01 -0.0606342 0.0428433 0.01 -0.0608798 0.044394 0.01 -0.0606342 0.0428433 -0.01 -0.0609619 0.0459619 0.01 -0.0608798 0.044394 -0.01 -0.0609619 0.0459619 -0.01 -0.044394 0.0310441 -0.01 -0.0428433 0.0312897 -0.01 -0.044394 0.0310441 0.01 -0.0428433 0.0312897 0.01 -0.0413267 0.0316961 -0.01 -0.0398609 0.0322588 -0.01 -0.0413267 0.0316961 0.01 -0.0384619 0.0329716 -0.01 -0.0398609 0.0322588 0.01 -0.0384619 0.0329716 0.01 -0.0371452 0.0338267 -0.01 -0.035925 0.0348148 -0.01 -0.0371452 0.0338267 0.01 -0.0348148 0.035925 -0.01 -0.035925 0.0348148 0.01 -0.0348148 0.035925 0.01 -0.0338267 0.0371452 -0.01 -0.0329716 0.0384619 -0.01 -0.0338267 0.0371452 0.01 -0.0322588 0.0398609 -0.01 -0.0329716 0.0384619 0.01 -0.0322588 0.0398609 0.01 -0.0316961 0.0413267 -0.01 -0.0312897 0.0428433 -0.01 -0.0316961 0.0413267 0.01 -0.0310441 0.044394 -0.01 -0.0312897 0.0428433 0.01 -0.0310441 0.044394 0.01 -0.0312897 0.0490806 0.01 -0.0310441 0.0475299 0.01 -0.0312897 0.0490806 -0.01 -0.0329716 0.0534619 0.01 -0.0322588 0.052063 0.01 -0.0329716 0.0534619 -0.01 -0.0316961 0.0505972 0.01 -0.0316961 0.0505972 -0.01 -0.0322588 0.052063 -0.01 -0.0348148 0.0559989 0.01 -0.035925 0.0571091 -0.01 -0.035925 0.0571091 0.01 -0.0338267 0.0547787 -0.01 -0.0348148 0.0559989 -0.01 -0.0338267 0.0547787 0.01 -0.0398609 0.0596651 -0.01 -0.0398609 0.0596651 0.01 -0.0384619 0.0589523 0.01 -0.0384619 0.0589523 -0.01 -0.0371452 0.0580972 0.01 -0.0371452 0.0580972 -0.01 -0.044394 0.0608798 0.01 -0.0428433 0.0606342 0.01 -0.044394 0.0608798 -0.01 -0.0413267 0.0602278 0.01 -0.0413267 0.0602278 -0.01 -0.0428433 0.0606342 -0.01 -0.0475299 0.0608798 0.01 -0.0490806 0.0606342 -0.01 -0.0490806 0.0606342 0.01 -0.0459619 0.0609619 -0.01 -0.0475299 0.0608798 -0.01 -0.0459619 0.0609619 0.01 -0.0534619 0.0589523 -0.01 -0.0534619 0.0589523 0.01 -0.052063 0.0596651 0.01 -0.052063 0.0596651 -0.01 -0.0505972 0.0602278 0.01 -0.0505972 0.0602278 -0.01 -0.0571091 0.0559989 0.01 -0.0559989 0.0571091 0.01 -0.0571091 0.0559989 -0.01 -0.0547787 0.0580972 0.01 -0.0547787 0.0580972 -0.01 -0.0559989 0.0571091 -0.01 -0.0580972 0.0547787 -0.01 -0.0580972 0.0547787 0.01 -0.0589523 0.0534619 -0.01 -0.0589523 0.0534619 0.01 -0.0596651 0.052063 0.01 -0.0596651 0.052063 -0.01 -0.0602278 0.0505972 -0.01 -0.0602278 0.0505972 0.01 -0.0606342 0.0490806 -0.01 -0.0606342 0.0490806 0.01 -0.0608798 0.0475299 0.01 -0.0608798 0.0475299 -0.01 -0.0042133 -0.109919 0.01 3.70592e-16 -0.11 0.01 3.97534e-16 -0.11 -0.01 0.11 2.02067e-17 0.01 0.109919 0.0042133 -0.01 0.11 2.02067e-17 -0.01 -0.0042133 -0.109919 -0.01 -0.00842042 -0.109677 0.01 -0.00842042 -0.109677 -0.01 -0.0126152 -0.109274 0.01 -0.0167914 -0.108711 0.01 -0.0126152 -0.109274 -0.01 -0.0167914 -0.108711 -0.01 -0.020943 -0.107988 0.01 -0.020943 -0.107988 -0.01 -0.0250639 -0.107106 0.01 -0.029148 -0.106068 0.01 -0.0250639 -0.107106 -0.01 -0.029148 -0.106068 -0.01 -0.0331893 -0.104874 0.01 -0.0331893 -0.104874 -0.01 -0.0371819 -0.103525 0.01 -0.0411199 -0.102025 0.01 -0.0371819 -0.103525 -0.01 -0.0411199 -0.102025 -0.01 -0.0449976 -0.100375 0.01 -0.0449976 -0.100375 -0.01 -0.0488092 -0.0985782 0.01 -0.0525492 -0.0966363 0.01 -0.0488092 -0.0985782 -0.01 -0.0525492 -0.0966363 -0.01 -0.0562121 -0.0945527 0.01 -0.0562121 -0.0945527 -0.01 -0.0597924 -0.0923302 0.01 -0.0632851 -0.0899722 0.01 -0.0597924 -0.0923302 -0.01 -0.0632851 -0.0899722 -0.01 -0.0666848 -0.0874822 0.01 -0.0666848 -0.0874822 -0.01 -0.0699867 -0.0848638 0.01 -0.0731858 -0.0821209 0.01 -0.0699867 -0.0848638 -0.01 -0.0731858 -0.0821209 -0.01 -0.0762776 -0.0792574 0.01 -0.0762776 -0.0792574 -0.01 -0.0792574 -0.0762776 0.01 -0.0821209 -0.0731858 0.01 -0.0792574 -0.0762776 -0.01 -0.0821209 -0.0731858 -0.01 -0.0848638 -0.0699867 0.01 -0.0848638 -0.0699867 -0.01 -0.0874822 -0.0666848 0.01 -0.0899722 -0.0632851 0.01 -0.0874822 -0.0666848 -0.01 -0.0899722 -0.0632851 -0.01 -0.0923302 -0.0597924 0.01 -0.0923302 -0.0597924 -0.01 -0.0945527 -0.0562121 0.01 -0.0966363 -0.0525492 0.01 -0.0945527 -0.0562121 -0.01 -0.0966363 -0.0525492 -0.01 -0.0985782 -0.0488092 0.01 -0.0985782 -0.0488092 -0.01 -0.100375 -0.0449976 0.01 -0.102025 -0.0411199 0.01 -0.100375 -0.0449976 -0.01 -0.102025 -0.0411199 -0.01 -0.103525 -0.0371819 0.01 -0.103525 -0.0371819 -0.01 -0.104874 -0.0331893 0.01 -0.106068 -0.029148 0.01 -0.104874 -0.0331893 -0.01 -0.106068 -0.029148 -0.01 -0.107106 -0.0250639 0.01 -0.107106 -0.0250639 -0.01 -0.107988 -0.020943 0.01 -0.108711 -0.0167914 0.01 -0.107988 -0.020943 -0.01 -0.108711 -0.0167914 -0.01 -0.109274 -0.0126152 0.01 -0.109274 -0.0126152 -0.01 -0.109677 -0.00842042 0.01 -0.109919 -0.0042133 0.01 -0.109677 -0.00842042 -0.01 -0.109919 -0.0042133 -0.01 -0.11 -2.02067e-17 0.01 -0.11 -2.02067e-17 -0.01 0.0042133 -0.109919 -0.01 0.0042133 -0.109919 0.01 0.00842042 -0.109677 -0.01 0.0126152 -0.109274 -0.01 0.00842042 -0.109677 0.01 0.0126152 -0.109274 0.01 0.0167914 -0.108711 -0.01 0.0167914 -0.108711 0.01 0.020943 -0.107988 -0.01 0.0250639 -0.107106 -0.01 0.020943 -0.107988 0.01 0.0250639 -0.107106 0.01 0.029148 -0.106068 -0.01 0.029148 -0.106068 0.01 0.0331893 -0.104874 -0.01 0.0371819 -0.103525 -0.01 0.0331893 -0.104874 0.01 0.0371819 -0.103525 0.01 0.0411199 -0.102025 -0.01 0.0411199 -0.102025 0.01 0.0449976 -0.100375 -0.01 0.0488092 -0.0985782 -0.01 0.0449976 -0.100375 0.01 0.0488092 -0.0985782 0.01 0.0525492 -0.0966363 -0.01 0.0525492 -0.0966363 0.01 0.0562121 -0.0945527 -0.01 0.0597924 -0.0923302 -0.01 0.0562121 -0.0945527 0.01 0.0597924 -0.0923302 0.01 0.0632851 -0.0899722 -0.01 0.0632851 -0.0899722 0.01 0.0666848 -0.0874822 -0.01 0.0699867 -0.0848638 -0.01 0.0666848 -0.0874822 0.01 0.0699867 -0.0848638 0.01 0.0731858 -0.0821209 -0.01 0.0731858 -0.0821209 0.01 0.0762776 -0.0792574 -0.01 0.0792574 -0.0762776 -0.01 0.0762776 -0.0792574 0.01 0.0792574 -0.0762776 0.01 0.0821209 -0.0731858 -0.01 0.0821209 -0.0731858 0.01 0.0848638 -0.0699867 -0.01 0.0874822 -0.0666848 -0.01 0.0848638 -0.0699867 0.01 0.0874822 -0.0666848 0.01 0.0899722 -0.0632851 -0.01 0.0899722 -0.0632851 0.01 0.0923302 -0.0597924 -0.01 0.0945527 -0.0562121 -0.01 0.0923302 -0.0597924 0.01 0.0945527 -0.0562121 0.01 0.0966363 -0.0525492 -0.01 0.0966363 -0.0525492 0.01 0.0985782 -0.0488092 -0.01 0.100375 -0.0449976 -0.01 0.0985782 -0.0488092 0.01 0.100375 -0.0449976 0.01 0.102025 -0.0411199 -0.01 0.102025 -0.0411199 0.01 0.103525 -0.0371819 -0.01 0.104874 -0.0331893 -0.01 0.103525 -0.0371819 0.01 0.104874 -0.0331893 0.01 0.106068 -0.029148 -0.01 0.106068 -0.029148 0.01 0.107106 -0.0250639 -0.01 0.107988 -0.020943 -0.01 0.107106 -0.0250639 0.01 0.107988 -0.020943 0.01 0.108711 -0.0167914 -0.01 0.108711 -0.0167914 0.01 0.109274 -0.0126152 -0.01 0.109677 -0.00842042 -0.01 0.109274 -0.0126152 0.01 0.109677 -0.00842042 0.01 0.109919 -0.0042133 -0.01 0.109919 -0.0042133 0.01 0.109677 0.00842042 0.01 0.109677 0.00842042 -0.01 0.109919 0.0042133 0.01 0.107988 0.020943 0.01 0.107988 0.020943 -0.01 0.108711 0.0167914 0.01 0.109274 0.0126152 0.01 0.108711 0.0167914 -0.01 0.109274 0.0126152 -0.01 0.106068 0.029148 0.01 0.104874 0.0331893 0.01 0.104874 0.0331893 -0.01 0.107106 0.0250639 -0.01 0.107106 0.0250639 0.01 0.106068 0.029148 -0.01 0.100375 0.0449976 -0.01 0.102025 0.0411199 0.01 0.100375 0.0449976 0.01 0.102025 0.0411199 -0.01 0.103525 0.0371819 -0.01 0.103525 0.0371819 0.01 0.0945527 0.0562121 0.01 0.0945527 0.0562121 -0.01 0.0966363 0.0525492 0.01 0.0985782 0.0488092 0.01 0.0966363 0.0525492 -0.01 0.0985782 0.0488092 -0.01 0.0899722 0.0632851 0.01 0.0874822 0.0666848 0.01 0.0874822 0.0666848 -0.01 0.0923302 0.0597924 -0.01 0.0923302 0.0597924 0.01 0.0899722 0.0632851 -0.01 0.0792574 0.0762776 -0.01 0.0821209 0.0731858 0.01 0.0792574 0.0762776 0.01 0.0821209 0.0731858 -0.01 0.0848638 0.0699867 -0.01 0.0848638 0.0699867 0.01 0.0699867 0.0848638 0.01 0.0699867 0.0848638 -0.01 0.0731858 0.0821209 0.01 0.0762776 0.0792574 0.01 0.0731858 0.0821209 -0.01 0.0762776 0.0792574 -0.01 0.0632851 0.0899722 0.01 0.0597924 0.0923302 0.01 0.0597924 0.0923302 -0.01 0.0666848 0.0874822 -0.01 0.0666848 0.0874822 0.01 0.0632851 0.0899722 -0.01 0.0488092 0.0985782 -0.01 0.0525492 0.0966363 0.01 0.0488092 0.0985782 0.01 0.0525492 0.0966363 -0.01 0.0562121 0.0945527 -0.01 0.0562121 0.0945527 0.01 0.0371819 0.103525 0.01 0.0371819 0.103525 -0.01 0.0411199 0.102025 0.01 0.0449976 0.100375 0.01 0.0411199 0.102025 -0.01 0.0449976 0.100375 -0.01 0.029148 0.106068 0.01 0.0250639 0.107106 0.01 0.0250639 0.107106 -0.01 0.0331893 0.104874 -0.01 0.0331893 0.104874 0.01 0.029148 0.106068 -0.01 0.0126152 0.109274 -0.01 0.0167914 0.108711 0.01 0.0126152 0.109274 0.01 0.0167914 0.108711 -0.01 0.020943 0.107988 -0.01 0.020943 0.107988 0.01 -9.09641e-17 0.11 0.01 -9.09641e-17 0.11 -0.01 0.0042133 0.109919 0.01 0.00842042 0.109677 0.01 0.0042133 0.109919 -0.01 0.00842042 0.109677 -0.01 -0.00842042 0.109677 0.01 -0.0126152 0.109274 0.01 -0.0126152 0.109274 -0.01 -0.0042133 0.109919 -0.01 -0.0042133 0.109919 0.01 -0.00842042 0.109677 -0.01 -0.0250639 0.107106 -0.01 -0.020943 0.107988 0.01 -0.0250639 0.107106 0.01 -0.020943 0.107988 -0.01 -0.0167914 0.108711 -0.01 -0.0167914 0.108711 0.01 -0.0371819 0.103525 0.01 -0.0371819 0.103525 -0.01 -0.0331893 0.104874 0.01 -0.029148 0.106068 0.01 -0.0331893 0.104874 -0.01 -0.029148 0.106068 -0.01 -0.0449976 0.100375 0.01 -0.0488092 0.0985782 0.01 -0.0488092 0.0985782 -0.01 -0.0411199 0.102025 -0.01 -0.0411199 0.102025 0.01 -0.0449976 0.100375 -0.01 -0.0597924 0.0923302 -0.01 -0.0562121 0.0945527 0.01 -0.0597924 0.0923302 0.01 -0.0562121 0.0945527 -0.01 -0.0525492 0.0966363 -0.01 -0.0525492 0.0966363 0.01 -0.0699867 0.0848638 0.01 -0.0699867 0.0848638 -0.01 -0.0666848 0.0874822 0.01 -0.0632851 0.0899722 0.01 -0.0666848 0.0874822 -0.01 -0.0632851 0.0899722 -0.01 -0.0762776 0.0792574 0.01 -0.0792574 0.0762776 0.01 -0.0792574 0.0762776 -0.01 -0.0731858 0.0821209 -0.01 -0.0731858 0.0821209 0.01 -0.0762776 0.0792574 -0.01 -0.0821209 0.0731858 0.01 -0.0821209 0.0731858 -0.01 -0.0848638 0.0699867 -0.01 -0.0848638 0.0699867 0.01 -0.0874822 0.0666848 0.01 -0.0874822 0.0666848 -0.01 -0.0899722 0.0632851 0.01 -0.0899722 0.0632851 -0.01 -0.0923302 0.0597924 -0.01 -0.0923302 0.0597924 0.01 -0.0945527 0.0562121 0.01 -0.0945527 0.0562121 -0.01 -0.0966363 0.0525492 0.01 -0.0966363 0.0525492 -0.01 -0.0985782 0.0488092 -0.01 -0.0985782 0.0488092 0.01 -0.100375 0.0449976 0.01 -0.100375 0.0449976 -0.01 -0.102025 0.0411199 0.01 -0.102025 0.0411199 -0.01 -0.103525 0.0371819 -0.01 -0.103525 0.0371819 0.01 -0.104874 0.0331893 0.01 -0.104874 0.0331893 -0.01 -0.106068 0.029148 0.01 -0.106068 0.029148 -0.01 -0.107106 0.0250639 -0.01 -0.107106 0.0250639 0.01 -0.107988 0.020943 0.01 -0.107988 0.020943 -0.01 -0.108711 0.0167914 0.01 -0.108711 0.0167914 -0.01 -0.109274 0.0126152 -0.01 -0.109274 0.0126152 0.01 -0.109677 0.00842042 0.01 -0.109677 0.00842042 -0.01 -0.109919 0.0042133 0.01 -0.109919 0.0042133 -0.01 -0.0848638 0.0699867 0.01 -0.0821209 0.0731858 0.01 -0.0589523 0.0534619 0.01 0.0309619 0.0459619 0.01 0.010037 0.0538528 0.01 0.0111472 0.054963 0.01 0.0488092 0.0985782 0.01 0.044394 0.0608798 0.01 0.0428433 0.0606342 0.01 0.0413267 0.0602278 0.01 0.0449976 0.100375 0.01 0.0525492 0.0966363 0.01 0.0562121 0.0945527 0.01 0.0459619 0.0609619 0.01 0.0490806 0.0606342 0.01 0.0597924 0.0923302 0.01 0.0632851 0.0899722 0.01 0.0310441 0.0475299 0.01 0.0121353 0.0561832 0.01 0.00881678 0.0528647 0.01 0.0310441 0.044394 0.01 0.0411199 0.102025 0.01 0.0137032 0.0711011 0.01 0.0666848 0.0874822 0.01 0.052063 0.0596651 0.01 0.0505972 0.0602278 0.01 0.0398609 0.0596651 0.01 0.0142658 0.0696353 0.01 0.0731858 0.0821209 0.01 0.0547787 0.0580972 0.01 0.0534619 0.0589523 0.01 0.0146722 0.0618813 0.01 0.0329716 0.0534619 0.01 0.0142658 0.0603647 0.01 0.0312897 0.0428433 0.01 0.015 0.065 0.01 0.035925 0.0571091 0.01 0.0348148 0.0559989 0.01 0.0792574 0.0762776 0.01 0.0559989 0.0571091 0.01 0.0762776 0.0792574 0.01 0.0149178 0.0665679 0.01 0.0371452 0.0580972 0.01 0.0821209 0.0731858 0.01 0.0580972 0.0547787 0.01 0.0129904 0.0725 0.01 0.0316961 0.0413267 0.01 0.0075 0.0520096 0.01 0.0121353 0.0738168 0.01 0.0371819 0.103525 0.01 0.0874822 0.0666848 0.01 0.0596651 0.052063 0.01 0.0848638 0.0699867 0.01 0.0111472 0.075037 0.01 0.029148 0.106068 0.01 0.0331893 0.104874 0.01 0.0899722 0.0632851 0.01 0.0606342 0.0490806 0.01 0.0602278 0.0505972 0.01 0.0250639 0.107106 0.01 0.010037 0.0761472 0.01 0.0608798 0.0475299 0.01 0.0923302 0.0597924 0.01 0.0945527 0.0562121 0.01 0.020943 0.107988 0.01 0.00881678 0.0771353 0.01 0.0075 0.0779904 0.01 0.00610105 0.0512968 0.01 0.0167914 0.108711 0.01 0.00610105 0.0787032 0.01 0.0126152 0.109274 0.01 0.0966363 0.0525492 0.01 0.0609619 0.0459619 0.01 0.00463525 0.0792658 0.01 0.00311868 0.0796722 0.01 0.00842042 0.109677 0.01 0.0608798 0.044394 0.01 0.00156793 0.0799178 0.01 -9.09641e-17 0.11 0.01 0.0042133 0.109919 0.01 0.0985782 0.0488092 0.01 -0.00156793 0.0799178 0.01 -0.0042133 0.109919 0.01 -4.24915e-18 0.08 0.01 0.0322588 0.0398609 0.01 -0.00842042 0.109677 0.01 -0.00311868 0.0796722 0.01 -0.00463525 0.0792658 0.01 0.00463525 0.0507342 0.01 0.0329716 0.0384619 0.01 -0.0167914 0.108711 0.01 -0.00610105 0.0787032 0.01 -0.0075 0.0779904 0.01 0.0606342 0.0428433 0.01 0.100375 0.0449976 0.01 0.0602278 0.0413267 0.01 -0.020943 0.107988 0.01 -0.00881678 0.0771353 0.01 -0.0250639 0.107106 0.01 0.00311868 0.0503278 0.01 -0.029148 0.106068 0.01 -0.010037 0.0761472 0.01 0.0665679 0.0149178 0.01 0.065 0.015 0.01 0.0571091 0.035925 0.01 -0.0129904 0.0725 0.01 -0.0371819 0.103525 0.01 -0.0121353 0.0738168 0.01 0.0559989 0.0348148 0.01 0.0634321 0.0149178 0.01 0.0547787 0.0338267 0.01 -0.0699867 0.0848638 0.01 -0.0534619 0.0589523 0.01 -0.0731858 0.0821209 0.01 -0.0899722 0.0632851 0.01 -0.0606342 0.0490806 0.01 -0.0923302 0.0597924 0.01 0.102025 0.0411199 0.01 0.0711011 0.0137032 0.01 0.0588989 0.0137032 0.01 0.0505972 0.0316961 0.01 0.052063 0.0322588 0.01 -0.102025 0.0411199 0.01 -0.0725 0.0129904 0.01 -0.103525 0.0371819 0.01 0.0771353 0.00881678 0.01 0.107106 0.0250639 0.01 0.107988 0.020943 0.01 -0.0771353 0.00881678 0.01 -0.0779904 0.0075 0.01 -0.107988 0.020943 0.01 0.054963 0.0111472 0.01 0.0538528 0.010037 0.01 0.0459619 0.0309619 0.01 -0.0796722 0.00311868 0.01 -0.0799178 0.00156793 0.01 -0.109919 0.0042133 0.01 0.0528647 0.00881678 0.01 0.044394 0.0310441 0.01 -0.0725 -0.0129904 0.01 -0.0711011 -0.0137032 0.01 -0.102025 -0.0411199 0.01 0.0799178 -0.00156793 0.01 0.08 9.41679e-18 0.01 0.109919 -0.0042133 0.01 0.0796722 -0.00311868 0.01 0.109677 -0.00842042 0.01 0.0512968 0.00610105 0.01 0.0507342 0.00463525 0.01 0.0398609 0.0322588 0.01 -0.052063 -0.0322588 0.01 -0.0603647 -0.0142658 0.01 -0.0588989 -0.0137032 0.01 0.107988 -0.020943 0.01 0.0771353 -0.00881678 0.01 0.0779904 -0.0075 0.01 -0.0602278 -0.0505972 0.01 -0.0899722 -0.0632851 0.01 -0.0606342 -0.0490806 0.01 0.075037 -0.0111472 0.01 0.0761472 -0.010037 0.01 0.106068 -0.029148 0.01 -0.0547787 -0.0580972 0.01 -0.0762776 -0.0792574 0.01 -0.0559989 -0.0571091 0.01 0.103525 -0.0371819 0.01 0.0738168 -0.0121353 0.01 0.104874 -0.0331893 0.01 -0.0597924 -0.0923302 0.01 -0.0632851 -0.0899722 0.01 -0.0490806 -0.0606342 0.01 0.0348148 -0.035925 0.01 0.00156793 -0.0500822 0.01 -4.24915e-18 -0.05 0.01 0.0966363 -0.0525492 0.01 0.0945527 -0.0562121 0.01 0.0609619 -0.0459619 0.01 -0.0371819 -0.103525 0.01 -0.0121353 -0.0738168 0.01 -0.0331893 -0.104874 0.01 0.0602278 -0.0505972 0.01 0.0606342 -0.0490806 0.01 0.0899722 -0.0632851 0.01 -0.020943 -0.107988 0.01 -0.00881678 -0.0771353 0.01 -0.0075 -0.0779904 0.01 0.0538528 -0.010037 0.01 0.044394 -0.0310441 0.01 0.0528647 -0.00881678 0.01 0.00311868 -0.0796722 0.01 0.0042133 -0.109919 0.01 0.00156793 -0.0799178 0.01 0.0547787 -0.0580972 0.01 0.0731858 -0.0821209 0.01 0.0534619 -0.0589523 0.01 0.0322588 -0.0398609 0.01 0.0316961 -0.0413267 0.01 0.00610105 -0.0512968 0.01 0.0632851 -0.0899722 0.01 0.0490806 -0.0606342 0.01 0.0505972 -0.0602278 0.01 0.0398609 -0.0596651 0.01 0.0137032 -0.0711011 0.01 0.0142658 -0.0696353 0.01 0.0459619 -0.0609619 0.01 0.0525492 -0.0966363 0.01 0.044394 -0.0608798 0.01 0.0475299 -0.0608798 0.01 0.0597924 -0.0923302 0.01 0.035925 -0.0348148 0.01 0.0500822 -0.00156793 0.01 0.0371452 -0.0338267 0.01 0.0149178 -0.0665679 0.01 0.035925 -0.0571091 0.01 0.0371452 -0.0580972 0.01 0.0146722 -0.0681187 0.01 0.0762776 -0.0792574 0.01 0.0559989 -0.0571091 0.01 0.0792574 -0.0762776 0.01 0.0666848 -0.0874822 0.01 0.0129904 -0.0725 0.01 0.0411199 -0.102025 0.01 0.015 -0.065 0.01 0.0348148 -0.0559989 0.01 0.0413267 -0.0316961 0.01 0.0520096 -0.0075 0.01 0.0428433 -0.0312897 0.01 0.0580972 -0.0547787 0.01 0.0821209 -0.0731858 0.01 0.00463525 -0.0792658 0.01 0.0126152 -0.109274 0.01 0.00842042 -0.109677 0.01 0.029148 -0.106068 0.01 0.0111472 -0.075037 0.01 0.0331893 -0.104874 0.01 0.0923302 -0.0597924 0.01 0.0561832 -0.0121353 0.01 0.0475299 -0.0310441 0.01 0.054963 -0.0111472 0.01 -0.00610105 -0.0787032 0.01 -0.00463525 -0.0792658 0.01 -0.0126152 -0.109274 0.01 0.00463525 -0.0507342 0.01 0.0608798 -0.0475299 0.01 0.0634321 -0.0149178 0.01 0.0547787 -0.0338267 0.01 0.0618813 -0.0146722 0.01 -0.0111472 -0.075037 0.01 -0.029148 -0.106068 0.01 -0.010037 -0.0761472 0.01 -0.0250639 -0.107106 0.01 0.035925 0.0348148 0.01 0.0500822 0.00156793 0.01 0.05 -1.60781e-17 0.01 0.102025 -0.0411199 0.01 0.100375 -0.0449976 0.01 0.0602278 -0.0413267 0.01 -0.0398609 -0.0596651 0.01 -0.0384619 -0.0589523 0.01 -0.0142658 -0.0696353 0.01 0.0725 -0.0129904 0.01 -0.0371452 -0.0580972 0.01 -0.035925 -0.0571091 0.01 -0.0149178 -0.0665679 0.01 -0.0137032 -0.0588989 0.01 -0.0142658 -0.0603647 0.01 -0.0322588 -0.052063 0.01 0.0371452 0.0338267 0.01 0.0503278 0.00311868 0.01 -0.0459619 -0.0609619 0.01 -0.0525492 -0.0966363 0.01 -0.0562121 -0.0945527 0.01 -0.052063 -0.0596651 0.01 -0.0666848 -0.0874822 0.01 -0.0699867 -0.0848638 0.01 0.0384619 0.0329716 0.01 0.107106 -0.0250639 0.01 -0.0731858 -0.0821209 0.01 -0.0534619 -0.0589523 0.01 -0.0821209 -0.0731858 0.01 -0.0580972 -0.0547787 0.01 -0.0792574 -0.0762776 0.01 0.108711 -0.0167914 0.01 0.0787032 -0.00610105 0.01 -0.0111472 -0.054963 0.01 -0.0309619 -0.0459619 0.01 -0.010037 -0.0538528 0.01 -0.0608798 -0.0475299 0.01 -0.0945527 -0.0562121 0.01 -0.0609619 -0.0459619 0.01 0.0413267 0.0316961 0.01 -0.065 -0.015 0.01 -0.0571091 -0.035925 0.01 -0.0665679 -0.0149178 0.01 -0.0538528 -0.010037 0.01 -0.0459619 -0.0309619 0.01 -0.054963 -0.0111472 0.01 0.0428433 0.0312897 0.01 0.0520096 0.0075 0.01 -0.0475299 -0.0310441 0.01 -0.0561832 -0.0121353 0.01 -0.104874 -0.0331893 0.01 -0.075037 -0.0111472 0.01 -0.0738168 -0.0121353 0.01 -0.106068 -0.029148 0.01 -0.107106 -0.0250639 0.01 -0.0761472 -0.010037 0.01 -0.109919 -0.0042133 0.01 -0.0796722 -0.00311868 0.01 -0.109677 -0.00842042 0.01 0.11 2.02067e-17 0.01 0.109919 0.0042133 0.01 0.0799178 0.00156793 0.01 -0.0459619 0.0309619 0.01 -0.0538528 0.010037 0.01 -0.054963 0.0111472 0.01 -0.075037 0.0111472 0.01 -0.106068 0.029148 0.01 -0.104874 0.0331893 0.01 0.0792658 0.00463525 0.01 0.109677 0.00842042 0.01 0.0796722 0.00311868 0.01 0.108711 0.0167914 0.01 0.0787032 0.00610105 0.01 0.0779904 0.0075 0.01 -0.0561832 0.0121353 0.01 -0.0475299 0.0310441 0.01 -0.065 0.015 0.01 -0.0559989 0.0348148 0.01 -0.0634321 0.0149178 0.01 0.0348148 0.035925 0.01 1.60781e-17 0.05 0.01 0.00156793 0.0500822 0.01 0.0575 0.0129904 0.01 0.0561832 0.0121353 0.01 0.0490806 0.0312897 0.01 -0.0571091 0.035925 0.01 -0.0665679 0.0149178 0.01 -0.0580972 0.0371452 0.01 -0.0490806 0.0312897 0.01 -0.0575 0.0129904 0.01 0.075037 0.0111472 0.01 0.106068 0.029148 0.01 0.0761472 0.010037 0.01 0.103525 0.0371819 0.01 0.0738168 0.0121353 0.01 0.0725 0.0129904 0.01 -0.0608798 0.0475299 0.01 -0.0945527 0.0562121 0.01 -0.0398609 0.0596651 0.01 -0.0413267 0.0602278 0.01 -0.0137032 0.0711011 0.01 0.0338267 0.0371452 0.01 0.0618813 0.0146722 0.01 0.0603647 0.0142658 0.01 0.0534619 0.0329716 0.01 -0.0874822 0.0666848 0.01 -0.0596651 0.052063 0.01 0.0681187 0.0146722 0.01 0.0580972 0.0371452 0.01 -0.0762776 0.0792574 0.01 -0.0547787 0.0580972 0.01 -0.0559989 0.0571091 0.01 -0.0459619 0.0609619 0.01 -0.0525492 0.0966363 0.01 -0.044394 0.0608798 0.01 0.0589523 0.0384619 0.01 -0.0411199 0.102025 0.01 -0.0331893 0.104874 0.01 -0.0111472 0.075037 0.01 0.0696353 0.0142658 0.01 0.0596651 0.0398609 0.01 0.0596651 -0.0398609 0.01 0.0589523 -0.0384619 0.01 0.0696353 -0.0142658 0.01 0.0603647 -0.0142658 0.01 0.0534619 -0.0329716 0.01 0.052063 -0.0322588 0.01 0.0848638 -0.0699867 0.01 0.0589523 -0.0534619 0.01 0.0596651 -0.052063 0.01 0.0507342 -0.00463525 0.01 0.0398609 -0.0322588 0.01 0.0384619 -0.0329716 0.01 0.0384619 -0.0589523 0.01 0.0413267 -0.0602278 0.01 0.00881678 -0.0771353 0.01 0.0250639 -0.107106 0.01 0.020943 -0.107988 0.01 0.0329716 -0.0384619 0.01 0.00311868 -0.0503278 0.01 -0.0411199 -0.102025 0.01 -0.0137032 -0.0711011 0.01 -0.0129904 -0.0725 0.01 -0.0129904 -0.0575 0.01 -0.0316961 -0.0505972 0.01 -0.0505972 -0.0602278 0.01 -0.0589523 -0.0534619 0.01 -0.0848638 -0.0699867 0.01 -0.0596651 -0.052063 0.01 -0.0634321 -0.0149178 0.01 -0.0618813 -0.0146722 0.01 -0.0547787 -0.0338267 0.01 -0.0505972 -0.0316961 0.01 -0.044394 -0.0310441 0.01 -0.0528647 -0.00881678 0.01 -0.109677 0.00842042 0.01 -0.109274 0.0126152 0.01 -0.0792658 0.00463525 0.01 -0.0761472 0.010037 0.01 -0.107106 0.0250639 0.01 -0.0738168 0.0121353 0.01 -0.0711011 0.0137032 0.01 -0.0596651 0.0398609 0.01 -0.0696353 0.0142658 0.01 -0.0588989 0.0137032 0.01 -0.0603647 0.0142658 0.01 -0.052063 0.0322588 0.01 -0.0371452 0.0580972 0.01 -0.0384619 0.0589523 0.01 -0.0146722 0.0681187 0.01 -0.0602278 0.0505972 0.01 -0.0449976 0.100375 0.01 -0.0792574 0.0762776 0.01 -0.0580972 0.0547787 0.01 -0.052063 0.0596651 0.01 -0.0666848 0.0874822 0.01 -0.0632851 0.0899722 0.01 -0.0505972 0.0602278 0.01 -0.0475299 0.0608798 0.01 -0.0562121 0.0945527 0.01 -0.0488092 0.0985782 0.01 -0.0428433 0.0606342 0.01 -0.0126152 0.109274 0.01 0.0384619 0.0589523 0.01 0.0149178 0.0634321 0.01 0.0146722 0.0681187 0.01 0.0338267 0.0547787 0.01 0.0322588 0.052063 0.01 0.0137032 0.0588989 0.01 0.0316961 0.0505972 0.01 0.0129904 0.0575 0.01 0.109274 -0.0126152 0.01 0.0792658 -0.00463525 0.01 3.70592e-16 -0.11 0.01 -0.0042133 -0.109919 0.01 -0.00156793 -0.0799178 0.01 -0.00311868 -0.0796722 0.01 -0.00842042 -0.109677 0.01 0.0711011 -0.0137032 0.01 0.0571091 -0.035925 0.01 0.0665679 -0.0149178 0.01 0.0580972 -0.0371452 0.01 0.065 -0.015 0.01 0.0559989 -0.0348148 0.01 0.0428433 -0.0606342 0.01 0.0449976 -0.100375 0.01 0.0874822 -0.0666848 0.01 0.0512968 -0.00610105 0.01 0.0488092 -0.0985782 0.01 0.052063 -0.0596651 0.01 0.0699867 -0.0848638 0.01 0.0503278 -0.00311868 0.01 0.0562121 -0.0945527 0.01 0.0312897 0.0490806 0.01 0.0475299 0.0608798 0.01 0.0699867 0.0848638 0.01 0.0571091 0.0559989 0.01 0.0589523 0.0534619 0.01 0.0681187 -0.0146722 0.01 0.0606342 -0.0428433 0.01 0.0985782 -0.0488092 0.01 0.0608798 -0.044394 0.01 0.0575 -0.0129904 0.01 0.0588989 -0.0137032 0.01 0.0505972 -0.0316961 0.01 -0.035925 0.0348148 0.01 -0.0316961 -0.0413267 0.01 -0.00610105 -0.0512968 0.01 -0.0075 -0.0520096 0.01 0.0142658 -0.0603647 0.01 0.0322588 -0.052063 0.01 0.0329716 -0.0534619 0.01 0.0149178 -0.0634321 0.01 0.0146722 -0.0618813 0.01 0.0338267 -0.0547787 0.01 0.0121353 -0.0738168 0.01 0.0167914 -0.108711 0.01 0.0075 -0.0779904 0.01 0.0312897 -0.0490806 0.01 0.0121353 -0.0561832 0.01 0.0310441 -0.0475299 0.01 0.0137032 -0.0588989 0.01 0.0129904 -0.0575 0.01 0.0316961 -0.0505972 0.01 -0.0923302 -0.0597924 0.01 -0.0384619 -0.0329716 0.01 -0.0398609 -0.0322588 0.01 -0.0507342 -0.00463525 0.01 -0.0413267 -0.0602278 0.01 0.0475299 0.0310441 0.01 0.104874 0.0331893 0.01 0.109274 0.0126152 0.01 0.0571091 -0.0559989 0.01 0.0371819 -0.103525 0.01 0.010037 -0.0761472 0.01 0.00610105 -0.0787032 0.01 0.010037 -0.0538528 0.01 0.0309619 -0.0459619 0.01 0.0111472 -0.054963 0.01 -0.0348148 0.035925 0.01 -0.00156793 0.0500822 0.01 -0.0167914 -0.108711 0.01 0.0338267 -0.0371452 0.01 -0.0329716 -0.0534619 0.01 -0.0146722 -0.0618813 0.01 -0.0348148 -0.0559989 0.01 -0.0149178 -0.0634321 0.01 -0.015 -0.065 0.01 -0.044394 -0.0608798 0.01 -0.0488092 -0.0985782 0.01 -0.0428433 -0.0606342 0.01 -0.0449976 -0.100375 0.01 -0.0608798 -0.044394 0.01 -0.0966363 -0.0525492 0.01 -0.0792658 -0.00463525 0.01 -0.109274 -0.0126152 0.01 -0.100375 -0.0449976 0.01 -0.0602278 -0.0413267 0.01 -0.0606342 -0.0428433 0.01 0.0459619 -0.0309619 0.01 0.0490806 -0.0312897 0.01 0.0075 -0.0520096 0.01 0.0312897 -0.0428433 0.01 0.00881678 -0.0528647 0.01 1.60781e-17 -0.08 0.01 -0.0146722 -0.0681187 0.01 -0.0338267 -0.0547787 0.01 -0.0312897 -0.0490806 0.01 -0.0121353 -0.0561832 0.01 -0.0475299 -0.0608798 0.01 -0.0310441 -0.0475299 0.01 -0.0571091 -0.0559989 0.01 -0.0874822 -0.0666848 0.01 -0.0580972 -0.0371452 0.01 -0.0596651 -0.0398609 0.01 -0.0696353 -0.0142658 0.01 -0.0589523 -0.0384619 0.01 -0.0322588 -0.0398609 0.01 -0.0329716 -0.0384619 0.01 -0.00463525 -0.0507342 0.01 -0.0348148 -0.035925 0.01 -0.00156793 -0.0500822 0.01 -0.0338267 -0.0371452 0.01 -0.0428433 -0.0312897 0.01 -0.0520096 -0.0075 0.01 -0.0413267 -0.0316961 0.01 -0.05 9.41679e-18 0.01 -0.035925 -0.0348148 0.01 -0.0500822 -0.00156793 0.01 -0.0799178 -0.00156793 0.01 -0.11 -2.02067e-17 0.01 -0.08 -1.60781e-17 0.01 -0.00311868 0.0503278 0.01 -0.0338267 0.0371452 0.01 -0.0329716 0.0384619 0.01 -0.108711 0.0167914 0.01 -0.0787032 0.00610105 0.01 -0.0503278 -0.00311868 0.01 -0.0371452 -0.0338267 0.01 -0.010037 0.0538528 0.01 -0.0309619 0.0459619 0.01 -0.0111472 0.054963 0.01 0.0310441 -0.044394 0.01 -0.0310441 -0.044394 0.01 -0.0312897 -0.0428433 0.01 -0.00881678 -0.0528647 0.01 -0.0985782 -0.0488092 0.01 -0.0681187 -0.0146722 0.01 -0.0559989 -0.0348148 0.01 -0.0490806 -0.0312897 0.01 -0.103525 -0.0371819 0.01 -0.0787032 -0.00610105 0.01 -0.108711 -0.0167914 0.01 -0.0779904 -0.0075 0.01 -0.107988 -0.020943 0.01 -0.0771353 -0.00881678 0.01 -0.0512968 -0.00610105 0.01 -0.0512968 0.00610105 0.01 -0.0413267 0.0316961 0.01 -0.0398609 0.0322588 0.01 -0.0520096 0.0075 0.01 -0.0428433 0.0312897 0.01 -0.0500822 0.00156793 0.01 -0.0503278 0.00311868 0.01 -0.0371452 0.0338267 0.01 -0.0312897 0.0428433 0.01 -0.0310441 0.044394 0.01 -0.00881678 0.0528647 0.01 -0.0316961 0.0413267 0.01 -0.00610105 0.0512968 0.01 -0.0322588 0.0398609 0.01 -0.00311868 -0.0503278 0.01 -0.0528647 0.00881678 0.01 -0.044394 0.0310441 0.01 -0.0575 -0.0129904 0.01 -0.0534619 -0.0329716 0.01 -0.0681187 0.0146722 0.01 -0.0618813 0.0146722 0.01 -0.0534619 0.0329716 0.01 -0.0505972 0.0316961 0.01 -0.0985782 0.0488092 0.01 -0.0608798 0.044394 0.01 -0.0606342 0.0428433 0.01 -0.0602278 0.0413267 0.01 -0.100375 0.0449976 0.01 -0.0966363 0.0525492 0.01 -0.0329716 0.0534619 0.01 -0.0142658 0.0603647 0.01 -0.0322588 0.052063 0.01 -0.0338267 0.0547787 0.01 -0.0149178 0.0634321 0.01 -0.0146722 0.0618813 0.01 -0.0316961 0.0505972 0.01 -0.0137032 0.0588989 0.01 -0.0129904 0.0575 0.01 -0.0310441 0.0475299 0.01 -0.0312897 0.0490806 0.01 -0.0121353 0.0561832 0.01 -0.0507342 0.00463525 0.01 -0.0384619 0.0329716 0.01 -0.0075 0.0520096 0.01 -0.00463525 0.0507342 0.01 -0.0348148 0.0559989 0.01 -0.035925 0.0571091 0.01 -0.015 0.065 0.01 -0.0609619 0.0459619 0.01 -0.0589523 0.0384619 0.01 -0.0547787 0.0338267 0.01 -0.0571091 0.0559989 0.01 -0.0142658 0.0696353 0.01 -0.0490806 0.0606342 0.01 -0.0597924 0.0923302 0.01 -0.0149178 0.0665679 0.01 -0.0848638 0.0699867 -0.01 -0.0589523 0.0534619 -0.01 -0.0821209 0.0731858 -0.01 0.0309619 0.0459619 -0.01 0.0111472 0.054963 -0.01 0.010037 0.0538528 -0.01 0.0488092 0.0985782 -0.01 0.0428433 0.0606342 -0.01 0.044394 0.0608798 -0.01 0.0449976 0.100375 -0.01 0.0413267 0.0602278 -0.01 0.0525492 0.0966363 -0.01 0.0459619 0.0609619 -0.01 0.0562121 0.0945527 -0.01 0.0490806 0.0606342 -0.01 0.0632851 0.0899722 -0.01 0.0597924 0.0923302 -0.01 0.0310441 0.0475299 -0.01 0.0121353 0.0561832 -0.01 0.00881678 0.0528647 -0.01 0.0310441 0.044394 -0.01 0.0411199 0.102025 -0.01 0.0137032 0.0711011 -0.01 0.0666848 0.0874822 -0.01 0.0505972 0.0602278 -0.01 0.052063 0.0596651 -0.01 0.0398609 0.0596651 -0.01 0.0142658 0.0696353 -0.01 0.0731858 0.0821209 -0.01 0.0534619 0.0589523 -0.01 0.0547787 0.0580972 -0.01 0.0146722 0.0618813 -0.01 0.0142658 0.0603647 -0.01 0.0329716 0.0534619 -0.01 0.0312897 0.0428433 -0.01 0.015 0.065 -0.01 0.0348148 0.0559989 -0.01 0.035925 0.0571091 -0.01 0.0792574 0.0762776 -0.01 0.0762776 0.0792574 -0.01 0.0559989 0.0571091 -0.01 0.0149178 0.0665679 -0.01 0.0371452 0.0580972 -0.01 0.0580972 0.0547787 -0.01 0.0821209 0.0731858 -0.01 0.0129904 0.0725 -0.01 0.0316961 0.0413267 -0.01 0.0075 0.0520096 -0.01 0.0371819 0.103525 -0.01 0.0121353 0.0738168 -0.01 0.0874822 0.0666848 -0.01 0.0848638 0.0699867 -0.01 0.0596651 0.052063 -0.01 0.0111472 0.075037 -0.01 0.0331893 0.104874 -0.01 0.029148 0.106068 -0.01 0.0899722 0.0632851 -0.01 0.0602278 0.0505972 -0.01 0.0606342 0.0490806 -0.01 0.0250639 0.107106 -0.01 0.010037 0.0761472 -0.01 0.0608798 0.0475299 -0.01 0.0945527 0.0562121 -0.01 0.0923302 0.0597924 -0.01 0.020943 0.107988 -0.01 0.0075 0.0779904 -0.01 0.00881678 0.0771353 -0.01 0.00610105 0.0512968 -0.01 0.0167914 0.108711 -0.01 0.0126152 0.109274 -0.01 0.00610105 0.0787032 -0.01 0.0609619 0.0459619 -0.01 0.0966363 0.0525492 -0.01 0.00463525 0.0792658 -0.01 0.00842042 0.109677 -0.01 0.00311868 0.0796722 -0.01 0.0608798 0.044394 -0.01 0.00156793 0.0799178 -0.01 0.0042133 0.109919 -0.01 -9.09641e-17 0.11 -0.01 0.0985782 0.0488092 -0.01 -0.00156793 0.0799178 -0.01 -4.24915e-18 0.08 -0.01 -0.0042133 0.109919 -0.01 0.0322588 0.0398609 -0.01 -0.00842042 0.109677 -0.01 -0.00463525 0.0792658 -0.01 -0.00311868 0.0796722 -0.01 0.00463525 0.0507342 -0.01 0.0329716 0.0384619 -0.01 -0.0167914 0.108711 -0.01 -0.0075 0.0779904 -0.01 -0.00610105 0.0787032 -0.01 0.0606342 0.0428433 -0.01 0.0602278 0.0413267 -0.01 0.100375 0.0449976 -0.01 -0.020943 0.107988 -0.01 -0.0250639 0.107106 -0.01 -0.00881678 0.0771353 -0.01 -0.000560476 0.00747903 -0.01 -0.00156793 0.0500822 -0.01 -0.00166891 0.00731196 -0.01 -0.029148 0.106068 -0.01 -0.010037 0.0761472 -0.01 0.0665679 0.0149178 -0.01 0.0571091 0.035925 -0.01 0.065 0.015 -0.01 -0.0129904 0.0725 -0.01 -0.0121353 0.0738168 -0.01 -0.0371819 0.103525 -0.01 0.0559989 0.0348148 -0.01 0.0547787 0.0338267 -0.01 0.0634321 0.0149178 -0.01 -0.0699867 0.0848638 -0.01 -0.0731858 0.0821209 -0.01 -0.0534619 0.0589523 -0.01 -0.0899722 0.0632851 -0.01 -0.0923302 0.0597924 -0.01 -0.0606342 0.0490806 -0.01 0.102025 0.0411199 -0.01 0.0711011 0.0137032 -0.01 0.0588989 0.0137032 -0.01 0.052063 0.0322588 -0.01 0.0505972 0.0316961 -0.01 -0.102025 0.0411199 -0.01 -0.103525 0.0371819 -0.01 -0.0725 0.0129904 -0.01 0.0771353 0.00881678 -0.01 0.107988 0.020943 -0.01 0.107106 0.0250639 -0.01 -0.0771353 0.00881678 -0.01 -0.107988 0.020943 -0.01 -0.0779904 0.0075 -0.01 0.054963 0.0111472 -0.01 0.0459619 0.0309619 -0.01 0.0538528 0.010037 -0.01 -0.0796722 0.00311868 -0.01 -0.109919 0.0042133 -0.01 -0.0799178 0.00156793 -0.01 0.0528647 0.00881678 -0.01 0.044394 0.0310441 -0.01 -0.0725 -0.0129904 -0.01 -0.102025 -0.0411199 -0.01 -0.0711011 -0.0137032 -0.01 0.0799178 -0.00156793 -0.01 0.109919 -0.0042133 -0.01 0.08 9.41679e-18 -0.01 0.0796722 -0.00311868 -0.01 0.109677 -0.00842042 -0.01 0.0512968 0.00610105 -0.01 0.0398609 0.0322588 -0.01 0.0507342 0.00463525 -0.01 -0.052063 -0.0322588 -0.01 -0.0588989 -0.0137032 -0.01 -0.0603647 -0.0142658 -0.01 0.107988 -0.020943 -0.01 0.0779904 -0.0075 -0.01 0.0771353 -0.00881678 -0.01 -0.0602278 -0.0505972 -0.01 -0.0606342 -0.0490806 -0.01 -0.0899722 -0.0632851 -0.01 0.075037 -0.0111472 -0.01 0.106068 -0.029148 -0.01 0.0761472 -0.010037 -0.01 -0.0547787 -0.0580972 -0.01 -0.0559989 -0.0571091 -0.01 -0.0762776 -0.0792574 -0.01 0.103525 -0.0371819 -0.01 0.104874 -0.0331893 -0.01 0.0738168 -0.0121353 -0.01 -0.0597924 -0.0923302 -0.01 -0.0490806 -0.0606342 -0.01 -0.0632851 -0.0899722 -0.01 0.00549789 -0.0051013 -0.01 0.00467617 -0.00586374 -0.01 0.0348148 -0.035925 -0.01 0.0966363 -0.0525492 -0.01 0.0609619 -0.0459619 -0.01 0.0945527 -0.0562121 -0.01 -0.0371819 -0.103525 -0.01 -0.0331893 -0.104874 -0.01 -0.0121353 -0.0738168 -0.01 0.0602278 -0.0505972 -0.01 0.0899722 -0.0632851 -0.01 0.0606342 -0.0490806 -0.01 -0.020943 -0.107988 -0.01 -0.0075 -0.0779904 -0.01 -0.00881678 -0.0771353 -0.01 0.0538528 -0.010037 -0.01 0.0528647 -0.00881678 -0.01 0.044394 -0.0310441 -0.01 0.00311868 -0.0796722 -0.01 0.00156793 -0.0799178 -0.01 0.0042133 -0.109919 -0.01 0.0547787 -0.0580972 -0.01 0.0534619 -0.0589523 -0.01 0.0731858 -0.0821209 -0.01 0.0322588 -0.0398609 -0.01 0.00610105 -0.0512968 -0.01 0.0316961 -0.0413267 -0.01 0.0632851 -0.0899722 -0.01 0.0505972 -0.0602278 -0.01 0.0490806 -0.0606342 -0.01 0.0398609 -0.0596651 -0.01 0.0142658 -0.0696353 -0.01 0.0137032 -0.0711011 -0.01 0.0459619 -0.0609619 -0.01 0.044394 -0.0608798 -0.01 0.0525492 -0.0966363 -0.01 0.0475299 -0.0608798 -0.01 0.0597924 -0.0923302 -0.01 0.0075 -1.37773e-18 -0.01 0.05 -1.60781e-17 -0.01 0.00741623 0.00111782 -0.01 0.0149178 -0.0665679 -0.01 0.0371452 -0.0580972 -0.01 0.035925 -0.0571091 -0.01 0.0146722 -0.0681187 -0.01 0.0762776 -0.0792574 -0.01 0.0792574 -0.0762776 -0.01 0.0559989 -0.0571091 -0.01 0.0666848 -0.0874822 -0.01 0.0129904 -0.0725 -0.01 0.0411199 -0.102025 -0.01 0.0348148 -0.0559989 -0.01 0.015 -0.065 -0.01 0.0413267 -0.0316961 -0.01 0.0428433 -0.0312897 -0.01 0.0520096 -0.0075 -0.01 0.0580972 -0.0547787 -0.01 0.0821209 -0.0731858 -0.01 0.00463525 -0.0792658 -0.01 0.00842042 -0.109677 -0.01 0.0126152 -0.109274 -0.01 0.029148 -0.106068 -0.01 0.0331893 -0.104874 -0.01 0.0111472 -0.075037 -0.01 0.0923302 -0.0597924 -0.01 0.0561832 -0.0121353 -0.01 0.054963 -0.0111472 -0.01 0.0475299 -0.0310441 -0.01 -0.00610105 -0.0787032 -0.01 -0.0126152 -0.109274 -0.01 -0.00463525 -0.0792658 -0.01 0.00463525 -0.0507342 -0.01 0.0608798 -0.0475299 -0.01 0.0634321 -0.0149178 -0.01 0.0618813 -0.0146722 -0.01 0.0547787 -0.0338267 -0.01 -0.029148 -0.106068 -0.01 -0.0111472 -0.075037 -0.01 -0.010037 -0.0761472 -0.01 -0.0250639 -0.107106 -0.01 0.00549789 0.0051013 -0.01 0.035925 0.0348148 -0.01 0.0348148 0.035925 -0.01 0.102025 -0.0411199 -0.01 0.0602278 -0.0413267 -0.01 0.100375 -0.0449976 -0.01 -0.0398609 -0.0596651 -0.01 -0.0142658 -0.0696353 -0.01 -0.0384619 -0.0589523 -0.01 0.0725 -0.0129904 -0.01 -0.0371452 -0.0580972 -0.01 -0.0149178 -0.0665679 -0.01 -0.035925 -0.0571091 -0.01 -0.0137032 -0.0588989 -0.01 -0.0322588 -0.052063 -0.01 -0.0142658 -0.0603647 -0.01 0.00274006 0.00698155 -0.01 -0.0459619 -0.0609619 -0.01 -0.0562121 -0.0945527 -0.01 -0.0525492 -0.0966363 -0.01 -0.052063 -0.0596651 -0.01 -0.0699867 -0.0848638 -0.01 -0.0666848 -0.0874822 -0.01 0.00311868 0.0503278 -0.01 0.107106 -0.0250639 -0.01 -0.0534619 -0.0589523 -0.01 -0.0731858 -0.0821209 -0.01 -0.0821209 -0.0731858 -0.01 -0.0792574 -0.0762776 -0.01 -0.0580972 -0.0547787 -0.01 0.0338267 0.0371452 -0.01 0.00467617 0.00586374 -0.01 0.108711 -0.0167914 -0.01 0.0787032 -0.00610105 -0.01 -0.0111472 -0.054963 -0.01 -0.010037 -0.0538528 -0.01 -0.0309619 -0.0459619 -0.01 -0.0608798 -0.0475299 -0.01 -0.0609619 -0.0459619 -0.01 -0.0945527 -0.0562121 -0.01 0.0413267 0.0316961 -0.01 -0.065 -0.015 -0.01 -0.0665679 -0.0149178 -0.01 -0.0571091 -0.035925 -0.01 -0.0538528 -0.010037 -0.01 -0.054963 -0.0111472 -0.01 -0.0459619 -0.0309619 -0.01 0.0520096 0.0075 -0.01 0.0428433 0.0312897 -0.01 -0.0561832 -0.0121353 -0.01 -0.0475299 -0.0310441 -0.01 -0.104874 -0.0331893 -0.01 -0.0738168 -0.0121353 -0.01 -0.075037 -0.0111472 -0.01 -0.106068 -0.029148 -0.01 -0.0761472 -0.010037 -0.01 -0.107106 -0.0250639 -0.01 -0.109919 -0.0042133 -0.01 -0.109677 -0.00842042 -0.01 -0.0796722 -0.00311868 -0.01 0.11 2.02067e-17 -0.01 0.109919 0.0042133 -0.01 0.0799178 0.00156793 -0.01 -0.0459619 0.0309619 -0.01 -0.054963 0.0111472 -0.01 -0.0538528 0.010037 -0.01 -0.075037 0.0111472 -0.01 -0.104874 0.0331893 -0.01 -0.106068 0.029148 -0.01 0.0792658 0.00463525 -0.01 0.0796722 0.00311868 -0.01 0.109677 0.00842042 -0.01 0.108711 0.0167914 -0.01 0.0779904 0.0075 -0.01 0.0787032 0.00610105 -0.01 -0.0475299 0.0310441 -0.01 -0.0561832 0.0121353 -0.01 -0.065 0.015 -0.01 -0.0634321 0.0149178 -0.01 -0.0559989 0.0348148 -0.01 -0.0338267 0.0371452 -0.01 -0.00467617 0.00586374 -0.01 -0.00375 0.00649519 -0.01 0.0575 0.0129904 -0.01 0.0490806 0.0312897 -0.01 0.0561832 0.0121353 -0.01 -0.0571091 0.035925 -0.01 -0.0580972 0.0371452 -0.01 -0.0665679 0.0149178 -0.01 -0.0490806 0.0312897 -0.01 -0.0575 0.0129904 -0.01 0.075037 0.0111472 -0.01 0.0761472 0.010037 -0.01 0.106068 0.029148 -0.01 0.103525 0.0371819 -0.01 0.0725 0.0129904 -0.01 0.0738168 0.0121353 -0.01 -0.0945527 0.0562121 -0.01 -0.0608798 0.0475299 -0.01 -0.0398609 0.0596651 -0.01 -0.0137032 0.0711011 -0.01 -0.0413267 0.0602278 -0.01 1.60781e-17 0.05 -0.01 0.000560476 0.00747903 -0.01 0.0618813 0.0146722 -0.01 0.0534619 0.0329716 -0.01 0.0603647 0.0142658 -0.01 -0.0874822 0.0666848 -0.01 -0.0596651 0.052063 -0.01 0.0681187 0.0146722 -0.01 0.0580972 0.0371452 -0.01 -0.0762776 0.0792574 -0.01 -0.0559989 0.0571091 -0.01 -0.0547787 0.0580972 -0.01 -0.0459619 0.0609619 -0.01 -0.044394 0.0608798 -0.01 -0.0525492 0.0966363 -0.01 0.0589523 0.0384619 -0.01 -0.0411199 0.102025 -0.01 -0.0111472 0.075037 -0.01 -0.0331893 0.104874 -0.01 0.0696353 0.0142658 -0.01 0.0596651 0.0398609 -0.01 -0.00274006 0.00698155 -0.01 -0.0329716 0.0384619 -0.01 0.0596651 -0.0398609 -0.01 0.0696353 -0.0142658 -0.01 0.0589523 -0.0384619 -0.01 0.0603647 -0.0142658 -0.01 0.052063 -0.0322588 -0.01 0.0534619 -0.0329716 -0.01 0.0848638 -0.0699867 -0.01 0.0596651 -0.052063 -0.01 0.0589523 -0.0534619 -0.01 0.0507342 -0.00463525 -0.01 0.0503278 -0.00311868 -0.01 0.0071668 -0.00221066 -0.01 0.0384619 -0.0589523 -0.01 0.0413267 -0.0602278 -0.01 0.00881678 -0.0771353 -0.01 0.020943 -0.107988 -0.01 0.0250639 -0.107106 -0.01 0.035925 -0.0348148 -0.01 0.0371452 -0.0338267 -0.01 0.00619679 -0.0042249 -0.01 -0.0411199 -0.102025 -0.01 -0.0129904 -0.0725 -0.01 -0.0137032 -0.0711011 -0.01 -0.0129904 -0.0575 -0.01 -0.0316961 -0.0505972 -0.01 -0.0505972 -0.0602278 -0.01 -0.0589523 -0.0534619 -0.01 -0.0596651 -0.052063 -0.01 -0.0848638 -0.0699867 -0.01 -0.0634321 -0.0149178 -0.01 -0.0547787 -0.0338267 -0.01 -0.0618813 -0.0146722 -0.01 -0.0505972 -0.0316961 -0.01 -0.044394 -0.0310441 -0.01 -0.0528647 -0.00881678 -0.01 -0.109677 0.00842042 -0.01 -0.0792658 0.00463525 -0.01 -0.109274 0.0126152 -0.01 -0.0761472 0.010037 -0.01 -0.107106 0.0250639 -0.01 -0.0738168 0.0121353 -0.01 -0.0711011 0.0137032 -0.01 -0.0696353 0.0142658 -0.01 -0.0596651 0.0398609 -0.01 -0.0588989 0.0137032 -0.01 -0.052063 0.0322588 -0.01 -0.0603647 0.0142658 -0.01 -0.0371452 0.0580972 -0.01 -0.0146722 0.0681187 -0.01 -0.0384619 0.0589523 -0.01 -0.0602278 0.0505972 -0.01 -0.0449976 0.100375 -0.01 -0.0580972 0.0547787 -0.01 -0.0792574 0.0762776 -0.01 -0.052063 0.0596651 -0.01 -0.0666848 0.0874822 -0.01 -0.0505972 0.0602278 -0.01 -0.0632851 0.0899722 -0.01 -0.0562121 0.0945527 -0.01 -0.0475299 0.0608798 -0.01 -0.0488092 0.0985782 -0.01 -0.0428433 0.0606342 -0.01 -0.0126152 0.109274 -0.01 0.0384619 0.0589523 -0.01 0.0149178 0.0634321 -0.01 0.0146722 0.0681187 -0.01 0.0338267 0.0547787 -0.01 0.0322588 0.052063 -0.01 0.0137032 0.0588989 -0.01 0.0316961 0.0505972 -0.01 0.0129904 0.0575 -0.01 0.109274 -0.0126152 -0.01 0.0792658 -0.00463525 -0.01 3.97534e-16 -0.11 -0.01 -0.00156793 -0.0799178 -0.01 -0.0042133 -0.109919 -0.01 -0.00842042 -0.109677 -0.01 -0.00311868 -0.0796722 -0.01 0.0711011 -0.0137032 -0.01 0.0571091 -0.035925 -0.01 0.0580972 -0.0371452 -0.01 0.0665679 -0.0149178 -0.01 0.065 -0.015 -0.01 0.0559989 -0.0348148 -0.01 0.0428433 -0.0606342 -0.01 0.0449976 -0.100375 -0.01 0.0874822 -0.0666848 -0.01 0.0512968 -0.00610105 -0.01 0.0398609 -0.0322588 -0.01 0.0488092 -0.0985782 -0.01 0.0699867 -0.0848638 -0.01 0.052063 -0.0596651 -0.01 0.0500822 0.00156793 -0.01 0.0503278 0.00311868 -0.01 0.0562121 -0.0945527 -0.01 0.00156793 0.0500822 -0.01 -0.0322588 0.0398609 -0.01 0.0312897 0.0490806 -0.01 0.0475299 0.0608798 -0.01 0.0699867 0.0848638 -0.01 0.0571091 0.0559989 -0.01 0.0589523 0.0534619 -0.01 0.0681187 -0.0146722 -0.01 0.0606342 -0.0428433 -0.01 0.0608798 -0.044394 -0.01 0.0985782 -0.0488092 -0.01 0.0575 -0.0129904 -0.01 0.0505972 -0.0316961 -0.01 0.0588989 -0.0137032 -0.01 0.00166891 0.00731196 -0.01 0.0500822 -0.00156793 -0.01 0.0384619 0.0329716 -0.01 0.0371452 0.0338267 -0.01 0.00675727 0.00325413 -0.01 -0.0316961 -0.0413267 -0.01 -0.0075 -0.0520096 -0.01 -0.00610105 -0.0512968 -0.01 0.0142658 -0.0603647 -0.01 0.0329716 -0.0534619 -0.01 0.0322588 -0.052063 -0.01 0.0149178 -0.0634321 -0.01 0.0338267 -0.0547787 -0.01 0.0146722 -0.0618813 -0.01 0.0121353 -0.0738168 -0.01 0.0075 -0.0779904 -0.01 0.0167914 -0.108711 -0.01 0.0312897 -0.0490806 -0.01 0.0310441 -0.0475299 -0.01 0.0121353 -0.0561832 -0.01 0.0137032 -0.0588989 -0.01 0.0316961 -0.0505972 -0.01 0.0129904 -0.0575 -0.01 -0.0923302 -0.0597924 -0.01 -0.0384619 -0.0329716 -0.01 -0.0507342 -0.00463525 -0.01 -0.0398609 -0.0322588 -0.01 -0.0413267 -0.0602278 -0.01 0.0475299 0.0310441 -0.01 0.104874 0.0331893 -0.01 0.109274 0.0126152 -0.01 0.0571091 -0.0559989 -0.01 0.0371819 -0.103525 -0.01 0.010037 -0.0761472 -0.01 0.00619679 0.0042249 -0.01 0.00610105 -0.0787032 -0.01 0.010037 -0.0538528 -0.01 0.0111472 -0.054963 -0.01 0.0309619 -0.0459619 -0.01 -0.0348148 0.035925 -0.01 -0.00549789 0.0051013 -0.01 -0.0167914 -0.108711 -0.01 0.00675727 -0.00325413 -0.01 -0.0329716 -0.0534619 -0.01 -0.0146722 -0.0618813 -0.01 -0.0348148 -0.0559989 -0.01 -0.015 -0.065 -0.01 -0.0149178 -0.0634321 -0.01 -0.0488092 -0.0985782 -0.01 -0.044394 -0.0608798 -0.01 -0.0428433 -0.0606342 -0.01 -0.0449976 -0.100375 -0.01 -0.0608798 -0.044394 -0.01 -0.0966363 -0.0525492 -0.01 -0.109274 -0.0126152 -0.01 -0.0792658 -0.00463525 -0.01 -0.100375 -0.0449976 -0.01 -0.0606342 -0.0428433 -0.01 -0.0602278 -0.0413267 -0.01 0.0459619 -0.0309619 -0.01 0.0490806 -0.0312897 -0.01 0.0075 -0.0520096 -0.01 0.00881678 -0.0528647 -0.01 0.0312897 -0.0428433 -0.01 1.60781e-17 -0.08 -0.01 -0.0146722 -0.0681187 -0.01 -0.0338267 -0.0547787 -0.01 -0.0312897 -0.0490806 -0.01 -0.0121353 -0.0561832 -0.01 -0.0475299 -0.0608798 -0.01 -0.0310441 -0.0475299 -0.01 -0.0571091 -0.0559989 -0.01 -0.0874822 -0.0666848 -0.01 -0.0580972 -0.0371452 -0.01 -0.0596651 -0.0398609 -0.01 -0.0589523 -0.0384619 -0.01 -0.0696353 -0.0142658 -0.01 -0.0322588 -0.0398609 -0.01 -0.00463525 -0.0507342 -0.01 -0.0329716 -0.0384619 -0.01 -4.24915e-18 -0.05 -0.01 -0.000560476 -0.00747903 -0.01 -0.00156793 -0.0500822 -0.01 -0.0428433 -0.0312897 -0.01 -0.0413267 -0.0316961 -0.01 -0.0520096 -0.0075 -0.01 -0.0503278 -0.00311868 -0.01 -0.0071668 -0.00221066 -0.01 -0.00741623 -0.00111782 -0.01 0.0338267 -0.0371452 -0.01 -0.0799178 -0.00156793 -0.01 -0.08 -1.60781e-17 -0.01 -0.11 -2.02067e-17 -0.01 -0.0371452 0.0338267 -0.01 -0.00675727 0.00325413 -0.01 -0.00619679 0.0042249 -0.01 -0.108711 0.0167914 -0.01 -0.0787032 0.00610105 -0.01 -0.035925 -0.0348148 -0.01 -0.00549789 -0.0051013 -0.01 -0.00619679 -0.0042249 -0.01 -0.010037 0.0538528 -0.01 -0.0111472 0.054963 -0.01 -0.0309619 0.0459619 -0.01 0.00741623 -0.00111782 -0.01 0.0329716 -0.0384619 -0.01 0.00375 -0.00649519 -0.01 0.0310441 -0.044394 -0.01 -0.0310441 -0.044394 -0.01 -0.00881678 -0.0528647 -0.01 -0.0312897 -0.0428433 -0.01 -0.0985782 -0.0488092 -0.01 -0.0681187 -0.0146722 -0.01 -0.0559989 -0.0348148 -0.01 -0.0490806 -0.0312897 -0.01 -0.103525 -0.0371819 -0.01 -0.108711 -0.0167914 -0.01 -0.0787032 -0.00610105 -0.01 -0.0779904 -0.0075 -0.01 -0.107988 -0.020943 -0.01 -0.0771353 -0.00881678 -0.01 -0.0512968 -0.00610105 -0.01 -0.0512968 0.00610105 -0.01 -0.0398609 0.0322588 -0.01 -0.0413267 0.0316961 -0.01 -0.0428433 0.0312897 -0.01 -0.0520096 0.0075 -0.01 0.00274006 -0.00698155 -0.01 -0.00675727 -0.00325413 -0.01 -0.0371452 -0.0338267 -0.01 -0.00741623 0.00111782 -0.01 -0.0500822 0.00156793 -0.01 -0.0075 -4.59243e-19 -0.01 -0.0338267 -0.0371452 -0.01 -0.00467617 -0.00586374 -0.01 -0.0348148 -0.035925 -0.01 -0.0312897 0.0428433 -0.01 -0.00881678 0.0528647 -0.01 -0.0310441 0.044394 -0.01 -0.00274006 -0.00698155 -0.01 -0.00375 -0.00649519 -0.01 -0.0316961 0.0413267 -0.01 -0.00610105 0.0512968 -0.01 -0.00166891 -0.00731196 -0.01 -0.00311868 -0.0503278 -0.01 0.00311868 -0.0503278 -0.01 0.000560476 -0.00747903 -0.01 0.00156793 -0.0500822 -0.01 0.00166891 -0.00731196 -0.01 -0.0528647 0.00881678 -0.01 -0.044394 0.0310441 -0.01 -0.0575 -0.0129904 -0.01 -0.0534619 -0.0329716 -0.01 -0.0681187 0.0146722 -0.01 -0.0618813 0.0146722 -0.01 -0.0534619 0.0329716 -0.01 -0.0505972 0.0316961 -0.01 -0.0985782 0.0488092 -0.01 -0.0606342 0.0428433 -0.01 -0.0608798 0.044394 -0.01 -0.0602278 0.0413267 -0.01 -0.100375 0.0449976 -0.01 -0.0966363 0.0525492 -0.01 -0.0329716 0.0534619 -0.01 -0.0322588 0.052063 -0.01 -0.0142658 0.0603647 -0.01 -0.0338267 0.0547787 -0.01 -0.0146722 0.0618813 -0.01 -0.0149178 0.0634321 -0.01 -0.0316961 0.0505972 -0.01 -0.0129904 0.0575 -0.01 -0.0137032 0.0588989 -0.01 -0.0310441 0.0475299 -0.01 -0.0121353 0.0561832 -0.01 -0.0312897 0.0490806 -0.01 -0.0503278 0.00311868 -0.01 -0.0507342 0.00463525 -0.01 -0.0071668 0.00221066 -0.01 -0.05 9.41679e-18 -0.01 -0.0075 0.0520096 -0.01 -0.00463525 0.0507342 -0.01 -0.035925 0.0348148 -0.01 -0.0348148 0.0559989 -0.01 -0.015 0.065 -0.01 -0.035925 0.0571091 -0.01 -0.0609619 0.0459619 -0.01 -0.0384619 0.0329716 -0.01 -0.0500822 -0.00156793 -0.01 -0.0589523 0.0384619 -0.01 -0.0547787 0.0338267 -0.01 -0.0571091 0.0559989 -0.01 -0.0142658 0.0696353 -0.01 -0.0490806 0.0606342 -0.01 -0.0597924 0.0923302 -0.01 -0.0149178 0.0665679 -0.01 -0.00311868 0.0503278 -0.01 0.00375 0.00649519 -0.01 0.0071668 0.00221066 -0.01 0.0384619 -0.0329716 -0.01 0.000560476 -0.00747903 -0.072 -0.000560476 -0.00747903 -0.01 0.000560476 -0.00747903 -0.01 -0.0075 3.78991e-18 -0.072 -0.00741623 0.00111782 -0.01 -0.0075 -4.59243e-19 -0.01 0.00166891 -0.00731196 -0.01 0.00166891 -0.00731196 -0.072 0.00274006 -0.00698155 -0.01 0.00274006 -0.00698155 -0.072 0.00375 -0.00649519 -0.072 0.00375 -0.00649519 -0.01 0.00467617 -0.00586374 -0.01 0.00467617 -0.00586374 -0.072 0.00549789 -0.0051013 -0.01 0.00549789 -0.0051013 -0.072 0.00619679 -0.0042249 -0.072 0.00619679 -0.0042249 -0.01 0.00675727 -0.00325413 -0.01 0.00675727 -0.00325413 -0.072 0.0071668 -0.00221066 -0.01 0.0071668 -0.00221066 -0.072 0.00741623 -0.00111782 -0.072 0.00741623 -0.00111782 -0.01 0.0075 -8.95755e-18 -0.072 0.0075 -1.37773e-18 -0.01 -0.000560476 -0.00747903 -0.072 -0.00166891 -0.00731196 -0.072 -0.00166891 -0.00731196 -0.01 -0.00274006 -0.00698155 -0.01 -0.00274006 -0.00698155 -0.072 -0.00375 -0.00649519 -0.072 -0.00375 -0.00649519 -0.01 -0.00467617 -0.00586374 -0.072 -0.00467617 -0.00586374 -0.01 -0.00549789 -0.0051013 -0.01 -0.00549789 -0.0051013 -0.072 -0.00619679 -0.0042249 -0.072 -0.00619679 -0.0042249 -0.01 -0.00675727 -0.00325413 -0.072 -0.00675727 -0.00325413 -0.01 -0.0071668 -0.00221066 -0.01 -0.0071668 -0.00221066 -0.072 -0.00741623 -0.00111782 -0.072 -0.00741623 -0.00111782 -0.01 -0.0071668 0.00221066 -0.072 -0.0071668 0.00221066 -0.01 -0.00741623 0.00111782 -0.072 -0.00549789 0.0051013 -0.072 -0.00549789 0.0051013 -0.01 -0.00619679 0.0042249 -0.072 -0.00675727 0.00325413 -0.072 -0.00619679 0.0042249 -0.01 -0.00675727 0.00325413 -0.01 -0.00375 0.00649519 -0.072 -0.00274006 0.00698155 -0.072 -0.00274006 0.00698155 -0.01 -0.00467617 0.00586374 -0.01 -0.00467617 0.00586374 -0.072 -0.00375 0.00649519 -0.01 0.000560476 0.00747903 -0.01 -0.000560476 0.00747903 -0.072 0.000560476 0.00747903 -0.072 -0.000560476 0.00747903 -0.01 -0.00166891 0.00731196 -0.01 -0.00166891 0.00731196 -0.072 0.00375 0.00649519 -0.072 0.00375 0.00649519 -0.01 0.00274006 0.00698155 -0.072 0.00166891 0.00731196 -0.072 0.00274006 0.00698155 -0.01 0.00166891 0.00731196 -0.01 0.00549789 0.0051013 -0.072 0.00619679 0.0042249 -0.01 0.00549789 0.0051013 -0.01 0.00467617 0.00586374 -0.01 0.00467617 0.00586374 -0.072 0.00675727 0.00325413 -0.01 0.00619679 0.0042249 -0.072 0.00675727 0.00325413 -0.072 0.0071668 0.00221066 -0.01 0.0071668 0.00221066 -0.072 0.00741623 0.00111782 -0.01 0.00741623 0.00111782 -0.072 -0.00549789 0.0051013 -0.072 -0.00375 0.00649519 -0.072 -0.00467617 0.00586374 -0.072 -0.00375 -0.00649519 -0.072 0.00741623 0.00111782 -0.072 0.0071668 0.00221066 -0.072 -0.00619679 0.0042249 -0.072 -0.00274006 0.00698155 -0.072 -0.00166891 0.00731196 -0.072 -0.00675727 0.00325413 -0.072 -0.000560476 0.00747903 -0.072 0.000560476 0.00747903 -0.072 -0.0071668 0.00221066 -0.072 -0.00741623 0.00111782 -0.072 0.00166891 0.00731196 -0.072 -0.0075 3.78991e-18 -0.072 0.00274006 0.00698155 -0.072 0.00549789 0.0051013 -0.072 0.00467617 0.00586374 -0.072 -0.00675727 -0.00325413 -0.072 -0.0071668 -0.00221066 -0.072 0.00375 0.00649519 -0.072 -0.00741623 -0.00111782 -0.072 -0.00467617 -0.00586374 -0.072 0.00675727 0.00325413 -0.072 -0.00619679 -0.0042249 -0.072 -0.00549789 -0.0051013 -0.072 0.00619679 0.0042249 -0.072 0.0075 -8.95755e-18 -0.072 -0.00166891 -0.00731196 -0.072 0.00741623 -0.00111782 -0.072 -0.00274006 -0.00698155 -0.072 0.00619679 -0.0042249 -0.072 0.00675727 -0.00325413 -0.072 0.00166891 -0.00731196 -0.072 0.000560476 -0.00747903 -0.072 0.0071668 -0.00221066 -0.072 -0.000560476 -0.00747903 -0.072 0.00375 -0.00649519 -0.072 0.00467617 -0.00586374 -0.072 0.00549789 -0.0051013 -0.072 0.00274006 -0.00698155 -0.072 - - - - - - - - - - 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 1.19249e-08 1 0 1.19249e-08 1 0 0.104528 0.994522 0 -1 8.74228e-08 0 -1 -1.50996e-07 -0 -0.994522 -0.104528 -0 0.207912 0.978148 0 0.104529 0.994522 0 0.309017 0.951056 0 0.207912 0.978148 0 0.309017 0.951056 0 0.406737 0.913545 0 0.5 0.866025 0 0.406737 0.913545 0 0.587785 0.809017 0 0.5 0.866025 0 0.587785 0.809017 0 0.669131 0.743145 0 0.743145 0.669131 0 0.669131 0.743145 0 0.809017 0.587785 0 0.743145 0.669131 0 0.809017 0.587785 0 0.866026 0.5 0 0.913546 0.406736 0 0.866025 0.5 0 0.951057 0.309017 0 0.913546 0.406736 0 0.951057 0.309017 0 0.978148 0.207912 0 0.994522 0.104528 0 0.978148 0.207912 0 1 -1.74846e-07 0 0.994522 0.104529 0 1 -1.74846e-07 0 -0.104528 0.994522 0 -0.207911 0.978148 0 -0.104528 0.994522 0 -0.207912 0.978148 0 -0.309017 0.951056 0 -0.406737 0.913545 0 -0.309017 0.951056 0 -0.5 0.866025 0 -0.406737 0.913545 0 -0.5 0.866025 0 -0.587785 0.809017 0 -0.669131 0.743145 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.669131 0.743145 0 -0.743145 0.669131 0 -0.809017 0.587785 0 -0.866025 0.5 0 -0.809017 0.587785 0 -0.913545 0.406737 0 -0.866025 0.5 0 -0.913545 0.406737 0 -0.951057 0.309017 0 -0.978148 0.207912 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.978148 0.207912 0 -0.994522 0.104528 0 -0.978148 -0.207912 -0 -0.994522 -0.104528 -0 -0.978148 -0.207912 -0 -0.866025 -0.5 -0 -0.913545 -0.406737 -0 -0.866025 -0.5 -0 -0.951056 -0.309017 -0 -0.951056 -0.309017 -0 -0.913545 -0.406737 -0 -0.743145 -0.669131 -0 -0.669131 -0.743145 -0 -0.669131 -0.743145 -0 -0.809017 -0.587785 -0 -0.743145 -0.669131 -0 -0.809017 -0.587785 -0 -0.406737 -0.913545 -0 -0.406737 -0.913545 -0 -0.5 -0.866025 -0 -0.5 -0.866025 -0 -0.587785 -0.809017 -0 -0.587785 -0.809017 -0 -0.104529 -0.994522 -0 -0.207912 -0.978148 -0 -0.104529 -0.994522 -0 -0.309017 -0.951056 -0 -0.309017 -0.951057 -0 -0.207912 -0.978148 -0 0.104528 -0.994522 0 0.207912 -0.978148 0 0.207912 -0.978148 0 7.54979e-08 -1 0 0.104528 -0.994522 0 -4.37114e-08 -1 -0 0.5 -0.866025 0 0.5 -0.866025 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.743145 -0.669131 0 0.669131 -0.743145 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.669131 -0.743145 0 0.809017 -0.587785 0 0.809017 -0.587785 0 0.866025 -0.5 0 0.866025 -0.5 0 0.913545 -0.406737 0 0.913545 -0.406737 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.978148 -0.207912 0 0.978148 -0.207912 0 0.994522 -0.104528 0 0.994522 -0.104528 0 -0.0383026 -0.999266 0 -1.19249e-08 -1 0 -1.19249e-08 -1 0 1 -8.74228e-08 0 0.999266 0.0383027 0 1 -8.74228e-08 0 -0.0383031 -0.999266 0 -0.076549 -0.997066 0 -0.0765494 -0.997066 0 -0.114683 -0.993402 0 -0.152649 -0.98828 0 -0.114683 -0.993402 0 -0.152649 -0.98828 0 -0.190391 -0.981708 0 -0.190391 -0.981708 0 -0.227854 -0.973695 0 -0.264981 -0.964253 0 -0.227854 -0.973695 0 -0.264981 -0.964253 0 -0.301721 -0.953396 0 -0.30172 -0.953396 0 -0.338017 -0.94114 0 -0.373817 -0.927502 0 -0.338017 -0.94114 0 -0.373817 -0.927502 0 -0.409068 -0.912504 0 -0.409069 -0.912503 0 -0.44372 -0.896165 0 -0.47772 -0.878512 0 -0.44372 -0.896165 0 -0.47772 -0.878512 0 -0.511019 -0.85957 0 -0.511019 -0.85957 0 -0.543567 -0.839366 0 -0.575319 -0.817929 0 -0.543568 -0.839365 0 -0.575319 -0.817929 0 -0.606225 -0.795293 0 -0.606225 -0.795293 0 -0.636243 -0.771489 0 -0.665326 -0.746553 0 -0.636242 -0.771489 0 -0.665325 -0.746553 0 -0.693432 -0.720522 0 -0.693433 -0.720521 0 -0.720521 -0.693433 0 -0.746553 -0.665326 0 -0.720522 -0.693432 0 -0.746553 -0.665326 0 -0.771489 -0.636242 0 -0.771489 -0.636242 0 -0.795293 -0.606226 0 -0.817929 -0.575319 0 -0.795293 -0.606226 0 -0.817929 -0.575319 0 -0.839365 -0.543568 0 -0.839365 -0.543568 0 -0.85957 -0.511018 0 -0.878512 -0.47772 0 -0.85957 -0.511019 0 -0.878512 -0.47772 0 -0.896166 -0.44372 0 -0.896166 -0.44372 0 -0.912504 -0.409069 0 -0.927503 -0.373817 0 -0.912504 -0.409068 0 -0.927503 -0.373817 0 -0.94114 -0.338017 0 -0.94114 -0.338017 0 -0.953396 -0.301721 0 -0.964253 -0.264982 0 -0.953396 -0.301721 0 -0.964254 -0.264981 0 -0.973695 -0.227854 0 -0.973695 -0.227853 0 -0.981708 -0.190391 0 -0.98828 -0.152649 0 -0.981708 -0.190391 0 -0.98828 -0.152649 0 -0.993402 -0.114683 0 -0.993402 -0.114684 0 -0.997066 -0.0765493 0 -0.999266 -0.0383029 0 -0.997066 -0.0765493 0 -0.999266 -0.0383024 0 -1 1.74846e-07 0 -1 -3.01992e-07 0 0.0383026 -0.999266 0 0.0383026 -0.999266 0 0.0765494 -0.997066 0 0.114683 -0.993402 0 0.0765489 -0.997066 0 0.114683 -0.993402 0 0.152649 -0.98828 0 0.152649 -0.98828 0 0.190391 -0.981708 0 0.227854 -0.973695 0 0.190391 -0.981708 0 0.227854 -0.973695 0 0.264981 -0.964254 0 0.264981 -0.964254 0 0.30172 -0.953396 0 0.338017 -0.94114 0 0.301721 -0.953396 0 0.338017 -0.94114 0 0.373817 -0.927502 0 0.373817 -0.927502 0 0.409068 -0.912504 0 0.44372 -0.896165 0 0.409068 -0.912504 0 0.44372 -0.896165 0 0.47772 -0.878512 0 0.47772 -0.878512 0 0.511019 -0.859569 0 0.543568 -0.839365 0 0.511019 -0.85957 0 0.543567 -0.839366 0 0.575319 -0.817929 0 0.575319 -0.817929 0 0.606225 -0.795293 0 0.636242 -0.771489 0 0.606226 -0.795293 0 0.636243 -0.771489 0 0.665326 -0.746553 0 0.665326 -0.746553 0 0.693432 -0.720522 0 0.720521 -0.693433 0 0.693432 -0.720522 0 0.720522 -0.693433 0 0.746553 -0.665326 0 0.746553 -0.665326 0 0.771489 -0.636242 0 0.795293 -0.606225 0 0.771489 -0.636243 0 0.795293 -0.606226 0 0.817929 -0.575319 0 0.817929 -0.575319 0 0.839365 -0.543568 0 0.85957 -0.511019 0 0.839366 -0.543567 0 0.85957 -0.511019 0 0.878512 -0.47772 0 0.878512 -0.47772 0 0.896166 -0.44372 0 0.912504 -0.409069 0 0.896166 -0.44372 0 0.912504 -0.409069 0 0.927502 -0.373817 0 0.927502 -0.373817 0 0.94114 -0.338017 0 0.953396 -0.30172 0 0.94114 -0.338017 0 0.953396 -0.301721 0 0.964253 -0.264982 0 0.964253 -0.264982 0 0.973695 -0.227853 0 0.981708 -0.190391 0 0.973695 -0.227854 0 0.981708 -0.190391 0 0.98828 -0.152649 0 0.98828 -0.152649 0 0.993402 -0.114684 0 0.997066 -0.0765493 0 0.993402 -0.114683 0 0.997066 -0.0765493 0 0.999266 -0.0383029 0 0.999266 -0.0383027 0 0.997066 0.0765491 0 0.997066 0.0765491 0 0.999266 0.0383027 0 0.981708 0.190391 0 0.981708 0.190391 0 0.98828 0.152649 0 0.993402 0.114684 0 0.98828 0.152649 0 0.993402 0.114683 0 0.964254 0.264981 0 0.953396 0.301721 0 0.953396 0.301721 0 0.973695 0.227853 0 0.973695 0.227853 0 0.964253 0.264982 0 0.912504 0.409069 0 0.927502 0.373817 0 0.912504 0.409069 0 0.927502 0.373817 0 0.94114 0.338017 0 0.94114 0.338017 0 0.85957 0.511019 0 0.85957 0.511019 0 0.878512 0.47772 0 0.896166 0.44372 0 0.878512 0.47772 0 0.896166 0.44372 0 0.817929 0.575319 0 0.795293 0.606225 0 0.795293 0.606225 0 0.839365 0.543568 0 0.839365 0.543568 0 0.817929 0.575319 0 0.720522 0.693433 0 0.746553 0.665326 0 0.720522 0.693433 0 0.746553 0.665326 0 0.771489 0.636242 0 0.771489 0.636243 0 0.636243 0.771489 0 0.636243 0.771489 0 0.665326 0.746553 0 0.693433 0.720522 0 0.665326 0.746553 0 0.693433 0.720522 0 0.575319 0.817929 0 0.543568 0.839365 0 0.543567 0.839365 0 0.606225 0.795293 0 0.606225 0.795293 0 0.575319 0.817929 0 0.44372 0.896166 0 0.47772 0.878512 0 0.44372 0.896166 0 0.47772 0.878512 0 0.511019 0.85957 0 0.511019 0.85957 0 0.338017 0.94114 0 0.338017 0.94114 0 0.373817 0.927502 0 0.409069 0.912504 0 0.373817 0.927502 0 0.409069 0.912504 0 0.264981 0.964253 0 0.227854 0.973695 0 0.227853 0.973695 0 0.301721 0.953396 0 0.301721 0.953396 0 0.264982 0.964253 0 0.114684 0.993402 0 0.152649 0.98828 0 0.114684 0.993402 0 0.152649 0.98828 0 0.190391 0.981708 0 0.190391 0.981708 0 4.37114e-08 1 0 -7.54979e-08 1 0 0.0383027 0.999266 0 0.0765491 0.997066 0 0.0383026 0.999266 0 0.0765494 0.997066 0 -0.0765493 0.997066 0 -0.114683 0.993402 0 -0.114683 0.993402 0 -0.0383028 0.999266 0 -0.0383027 0.999266 0 -0.0765493 0.997066 0 -0.227854 0.973695 0 -0.190391 0.981708 0 -0.227854 0.973695 0 -0.190391 0.981708 0 -0.152649 0.98828 0 -0.152649 0.98828 0 -0.338017 0.94114 0 -0.338017 0.94114 0 -0.301721 0.953396 0 -0.264982 0.964253 0 -0.301721 0.953396 0 -0.264982 0.964253 0 -0.409069 0.912504 0 -0.44372 0.896166 0 -0.44372 0.896166 0 -0.373817 0.927502 0 -0.373817 0.927502 0 -0.409069 0.912504 0 -0.543568 0.839365 0 -0.511019 0.85957 0 -0.543568 0.839365 0 -0.511019 0.85957 0 -0.47772 0.878512 0 -0.47772 0.878512 0 -0.636242 0.771489 0 -0.636243 0.771489 0 -0.606225 0.795293 0 -0.575319 0.817929 0 -0.606225 0.795293 0 -0.575319 0.817929 0 -0.693433 0.720522 0 -0.720522 0.693433 0 -0.720522 0.693433 0 -0.665326 0.746553 0 -0.665326 0.746553 0 -0.693432 0.720522 0 -0.746553 0.665326 0 -0.746553 0.665326 0 -0.771489 0.636242 0 -0.771489 0.636242 0 -0.795293 0.606225 0 -0.795293 0.606225 0 -0.817929 0.575319 0 -0.817929 0.575319 0 -0.839365 0.543568 0 -0.839365 0.543568 0 -0.85957 0.511019 0 -0.85957 0.511019 0 -0.878512 0.47772 0 -0.878512 0.47772 0 -0.896166 0.44372 0 -0.896166 0.44372 0 -0.912504 0.409069 0 -0.912504 0.409069 0 -0.927502 0.373817 0 -0.927502 0.373817 0 -0.94114 0.338017 0 -0.94114 0.338017 0 -0.953396 0.301721 0 -0.953396 0.301721 0 -0.964253 0.264982 0 -0.964253 0.264982 0 -0.973695 0.227854 0 -0.973695 0.227854 0 -0.981708 0.190391 0 -0.981708 0.190391 0 -0.98828 0.152649 0 -0.98828 0.152649 0 -0.993402 0.114683 0 -0.993402 0.114683 0 -0.997066 0.0765492 0 -0.997066 0.0765493 0 -0.999266 0.0383027 0 -0.999266 0.0383027 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0.0747303 -0.997204 0 -0.0747303 -0.997204 0 0.0747303 -0.997204 0 -1 -8.74228e-08 0 -0.988831 0.149042 0 -1 -8.74228e-08 0 0.222521 -0.974928 0 0.222521 -0.974928 0 0.365341 -0.930874 0 0.365341 -0.930874 0 0.5 -0.866025 0 0.5 -0.866025 0 0.62349 -0.781831 0 0.62349 -0.781831 0 0.733052 -0.680173 0 0.733052 -0.680173 0 0.826239 -0.56332 0 0.826239 -0.56332 0 0.900969 -0.433884 0 0.900969 -0.433884 0 0.955573 -0.294755 0 0.955573 -0.294755 0 0.988831 -0.149042 0 0.988831 -0.149042 0 1 1.74846e-07 0 1 -3.01992e-07 0 -0.0747303 -0.997204 0 -0.222521 -0.974928 0 -0.222521 -0.974928 0 -0.365341 -0.930874 0 -0.365341 -0.930874 0 -0.5 -0.866025 0 -0.5 -0.866025 0 -0.62349 -0.781831 0 -0.62349 -0.781832 0 -0.733052 -0.680173 0 -0.733052 -0.680173 0 -0.826239 -0.56332 0 -0.826239 -0.56332 0 -0.900969 -0.433884 0 -0.900969 -0.433884 0 -0.955573 -0.294755 0 -0.955573 -0.294755 0 -0.988831 -0.149042 0 -0.988831 -0.149042 0 -0.955573 0.294755 0 -0.955573 0.294755 0 -0.988831 0.149042 0 -0.733052 0.680173 0 -0.733052 0.680173 0 -0.826239 0.56332 0 -0.900969 0.433884 0 -0.826239 0.56332 0 -0.900969 0.433884 0 -0.5 0.866025 0 -0.365341 0.930874 0 -0.365341 0.930874 0 -0.62349 0.781831 0 -0.62349 0.781832 0 -0.5 0.866026 0 0.07473 0.997204 0 -0.0747302 0.997204 0 0.0747301 0.997204 0 -0.07473 0.997204 0 -0.222521 0.974928 0 -0.222521 0.974928 0 0.5 0.866025 0 0.5 0.866025 0 0.365341 0.930874 0 0.222521 0.974928 0 0.365341 0.930874 0 0.222521 0.974928 0 0.733052 0.680173 0 0.826239 0.56332 0 0.733052 0.680173 0 0.62349 0.781832 0 0.62349 0.781832 0 0.900969 0.433884 0 0.826239 0.56332 0 0.900969 0.433884 0 0.955573 0.294755 0 0.955573 0.294755 0 0.988831 0.149042 0 0.988831 0.149042 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 - - - - - - - - - - - - - - -

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

-
-
-
- - - - 0.07241 0.0847184 0.0126994 0.0732981 0.0820207 0.01 0.076297 0.0812353 0.0126994 -0.101913 0.0451006 0.0126994 -0.103522 0.0412741 0.0126994 -0.101627 0.042095 0.01 -0.066145 0.087891 0.01 -0.066147 0.0896939 0.0126994 -0.0685842 0.0860012 0.01 -0.0741374 -0.0910265 0.021483 -0.0696789 -0.094483 0.021483 -0.068353 -0.0926852 0.0185002 -0.0703795 0.0864126 0.0126994 -0.100406 0.0449288 0.01 0.111179 -0.00773005 0.0126994 0.109827 -0.00616737 0.01 0.109611 -0.00924536 0.01 -0.0709692 0.0840439 0.01 -0.100118 0.0489572 0.0126994 -0.0991067 0.0477269 0.01 -0.0840512 0.0854476 0.0244418 -0.0823259 0.0836937 0.021483 -0.0799963 0.0892552 0.0244418 -0.0981274 0.0528339 0.0126994 -0.0977292 0.0504877 0.01 -0.0959339 0.0567195 0.0126994 -0.0947445 0.0558881 0.01 -0.0931399 0.0585232 0.01 -0.102768 0.039228 0.01 -0.0962747 0.0532089 0.01 -0.078153 0.0794514 0.0126994 -0.0799329 0.0755694 0.01 -0.077782 0.0777815 0.01 -0.0909087 0.0644673 0.0126994 -0.0935298 0.0606018 0.0126994 -0.0914618 0.0611124 0.01 -0.0878913 0.0661447 0.01 -0.0897118 0.0636538 0.01 -0.0820207 0.0732981 0.01 -0.0849926 0.0720879 0.0126994 -0.0840443 0.0709687 0.01 -0.0880645 0.0683012 0.0126994 -0.0860017 0.0685836 0.01 -0.0816895 0.0758106 0.0126994 -0.0755698 0.0799325 0.01 -0.0743826 0.0829918 0.0126994 -0.0732982 0.0820206 0.01 -0.063654 0.0897116 0.01 -0.0570161 0.0957579 0.0126994 -0.0558884 0.0947443 0.01 -0.0532093 0.0962744 0.01 -0.036938 0.106976 0.0155526 -0.0424464 0.104913 0.0155526 -0.0417986 0.103312 0.0126994 -0.0477275 0.0991065 0.01 -0.0521346 0.0985007 0.0126994 -0.0504884 0.0977288 0.01 -0.0375874 0.108857 0.0185002 -0.0431926 0.106757 0.0185002 -0.0800817 0.108589 0.0368012 -0.0781099 0.105915 0.0348514 -0.0746859 0.112369 0.0368012 -0.0486269 0.104394 0.0185002 -0.0477868 0.10259 0.0155526 -0.0573176 0.108293 0.0273172 -0.0560692 0.105935 0.0244418 -0.0517357 0.111068 0.0273172 -0.103991 0.0806538 0.0348514 -0.100364 0.0851253 0.0348514 -0.102897 0.0872742 0.0368012 -0.0549184 0.10376 0.021483 -0.0506089 0.108649 0.0244418 -0.0694055 0.104424 0.0300502 -0.0656978 0.110339 0.0325813 -0.0710835 0.106949 0.0325813 -0.0673277 0.113076 0.0348514 -0.0728469 0.109602 0.0348514 -0.0626843 0.105278 0.0273172 -0.058655 0.11082 0.0300502 -0.064147 0.107734 0.0300502 -0.134661 0.0725043 0.039724 -0.131384 0.0707399 0.0402139 -0.131651 0.0778366 0.039724 -0.0600731 0.113499 0.0325813 -0.0690273 0.115931 0.0368012 -0.0440305 0.108828 0.021483 -0.0495701 0.106419 0.021483 -0.0765904 0.115234 0.0383714 -0.0821238 0.111358 0.0383714 -0.0873787 0.107284 0.0383714 -0.0842256 0.114208 0.0395028 -0.0896149 0.11003 0.0395028 -0.0559647 0.138325 0.0402139 -0.0614487 0.13192 0.0401362 -0.0545816 0.134907 0.0401362 -0.0573606 0.141775 0.039724 -0.0645773 0.138637 0.039724 -0.0630058 0.135263 0.0402139 -0.14402 0.0704249 0.0371966 -0.144299 0.0776938 0.0352405 -0.147226 0.071993 0.0352405 -0.104555 0.116656 0.0387046 -0.10725 0.109032 0.039724 -0.102076 0.11389 0.039724 -0.10464 0.106378 0.0402139 -0.0995917 0.111119 0.0402139 -0.150187 0.0808637 0.0301473 -0.147322 0.0793213 0.0328772 -0.146829 0.0868108 0.0301473 -0.094232 0.115699 0.0402139 -0.0965824 0.118585 0.039724 -0.106999 0.119384 0.0371966 -0.109854 0.111679 0.0387046 -0.157225 0.0929573 0.0124252 -0.16082 0.0865891 0.0124252 -0.159312 0.0857767 0.0163769 -0.127602 0.108228 0.0328772 -0.130084 0.110333 0.0301473 -0.132214 0.102543 0.0328772 -0.112423 0.114291 0.0371966 -0.114926 0.116836 0.0352405 -0.11751 0.109054 0.0371966 -0.125028 0.11603 0.0301473 -0.122643 0.113817 0.0328772 -0.139366 0.10809 0.0237508 -0.141611 0.100422 0.0270916 -0.137181 0.106395 0.0270916 -0.134785 0.104537 0.0301473 -0.132395 0.112293 0.0270916 -0.149439 0.0883536 0.0270916 -0.148016 0.0959054 0.0237508 -0.15182 0.0897614 0.0237508 -0.141309 0.109597 0.0201657 -0.143867 0.102023 0.0237508 -0.114825 0.106562 0.0387046 -0.145873 0.103445 0.0201657 -0.147592 0.104664 0.0163769 -0.150079 0.0972421 0.0201657 -0.142974 0.110888 0.0163769 -0.12898 0.131123 0.00835136 -0.12954 0.131692 0.00419604 -0.134817 0.125114 0.00835136 -0.159249 0.0941535 3.35051e-17 -0.16289 0.0877033 3.2731e-17 -0.162647 0.0875728 0.00419604 -0.164083 0.0802356 -0.0124252 -0.16523 0.0807966 -0.00835136 -0.16082 0.0865891 -0.0124252 -0.14899 0.105655 0.0124252 -0.151847 0.0983881 0.0163769 -0.159012 0.0940133 0.00419604 -0.155258 0.100598 3.29075e-17 -0.159012 0.0940133 -0.00419604 -0.162647 0.0875728 -0.00419604 -0.155027 0.100448 -0.00419604 -0.155027 0.100448 0.00419604 -0.154357 0.100014 0.00835136 -0.150682 0.106855 0.00419604 -0.167025 0.073915 -0.0124252 -0.162543 0.0794828 -0.0163769 -0.165458 0.0732215 -0.0163769 -0.159312 0.0857767 -0.0163769 -0.161283 0.0713739 -0.0237508 -0.163531 0.0723687 -0.0201657 -0.158442 0.0774771 -0.0237508 -0.16807 0.0670092 -0.0163769 -0.166113 0.0662287 -0.0201657 -0.147322 0.0793213 -0.0328772 -0.150187 0.0808637 -0.0301473 -0.144029 0.0851549 -0.0328772 -0.163829 0.0653183 -0.0237508 -0.156192 0.0496245 -0.0352405 -0.161118 0.0451288 -0.0328772 -0.159464 0.050664 -0.0328772 -0.158753 0.0702544 -0.0270916 -0.16126 0.0642938 -0.0270916 -0.154337 0.0551252 -0.0352405 -0.15757 0.0562799 -0.0328772 -0.15279 0.0485437 -0.0371966 -0.157812 0.0442028 -0.0352405 -0.158444 0.0631711 -0.0301473 -0.155421 0.0619662 -0.0328772 -0.160634 0.0573743 -0.0301473 -0.143687 0.0402465 -0.0402139 -0.148576 0.0362725 -0.039724 -0.147271 0.0412503 -0.039724 -0.149299 0.0474345 -0.0387046 -0.154375 0.0432401 -0.0371966 -0.061113 0.0914614 0.01 -0.06169 0.0928157 0.0126994 -0.15061 0.0265883 -0.039724 -0.146042 0.0306195 -0.0402139 -0.146945 0.0259413 -0.0402139 -0.139746 0.0246702 -0.0395028 -0.135421 0.0283927 -0.0383714 -0.136258 0.0240546 -0.0383714 -0.134418 0.032816 -0.0383714 -0.138887 0.0291193 -0.0395028 -0.13187 0.0418969 -0.0383714 -0.136647 0.0382746 -0.0395028 -0.135245 0.0429691 -0.0395028 -0.14496 0.0353898 -0.0402139 -0.141378 0.0345152 -0.0401362 -0.127094 0.0183821 -0.0325813 -0.126461 0.0223251 -0.0325813 -0.123476 0.0217981 -0.0300502 -0.13287 0.0234565 -0.0368012 -0.132054 0.0276866 -0.0368012 -0.124094 0.0179482 -0.0300502 -0.124581 0.0141825 -0.0300502 -0.127593 0.0145254 -0.0325813 -0.130758 0.0148857 -0.0348514 -0.122096 0.0102639 -0.0273172 -0.12174 0.0138591 -0.0273172 -0.119089 0.0135572 -0.0244418 -0.119437 0.0100403 -0.0244418 -0.12234 0.00675494 -0.0273172 -0.149685 0.0313832 -0.039724 -0.118033 0.0208371 -0.0244418 -0.118623 0.0171569 -0.0244418 -0.121265 0.0175389 -0.0273172 -0.111449 0 -0.0127028 -0.111406 0.00303201 -0.0126994 -0.11 0 -0.01 -0.113032 0 -0.0153294 -0.113132 0.003079 -0.0155526 -0.111277 0.00614412 -0.0126994 -0.115121 0.00313313 -0.0185002 -0.11473 0 -0.0178833 -0.112448 0.0128012 -0.0155526 -0.112776 0.00948044 -0.0155526 -0.114759 0.0096471 -0.0185002 -0.104953 0.0374866 0.0126994 -0.103827 0.0363304 0.01 -0.106215 0.033746 0.0126994 -0.0585238 0.0931395 0.01 -0.104805 0.0334044 0.01 -0.105701 0.0304516 0.01 -0.107317 0.0300591 0.0126994 -0.106513 0.027475 0.01 -0.107242 0.0244771 0.01 -0.108267 0.0264318 0.0126994 -0.0470575 0.101025 0.0126994 -0.0449289 0.100406 0.01 -0.107886 0.0214598 0.01 -0.109075 0.022869 0.0126994 -0.10975 0.0193749 0.0126994 -0.108446 0.0184253 0.01 -0.0420955 0.101627 0.01 -0.10892 0.0153766 0.01 -0.110299 0.015953 0.0126994 -0.0392287 0.102767 0.01 -0.101474 0.0787013 0.0325813 -0.102278 0.0725301 0.0300502 -0.0990786 0.0768435 0.0300502 -0.0363743 0.105344 0.0126994 -0.0613191 0.102985 0.0244418 -0.0312801 0.108766 0.0155526 -0.110766 0.0232234 0.0155526 -0.0363309 0.103827 0.01 -0.109308 0.012316 0.01 -0.110732 0.0126059 0.0126994 -0.0334045 0.104805 0.01 -0.111055 0.00933575 0.0126994 -0.109611 0.00924536 0.01 -0.0308027 0.107106 0.0126994 -0.109827 0.00616737 0.01 -0.0254931 0.110266 0.0155526 -0.0274758 0.106513 0.01 -0.0304523 0.105701 0.01 -0.025104 0.108583 0.0126994 -0.111277 0.00614412 0.0126994 -0.0244774 0.107242 0.01 -0.113002 0.00623934 0.0155526 -0.111406 0.00303201 0.0126994 -0.0214601 0.107886 0.01 -0.109957 0.00308534 0.01 -0.11 0 0.01 -0.0193002 0.109763 0.0126994 -0.0136223 0.112351 0.0155526 -0.0195993 0.111464 0.0155526 -0.0153772 0.10892 0.01 -0.0184261 0.108446 0.01 -0.0134144 0.110637 0.0126994 -0.00758704 0.11292 0.0155526 -0.0123162 0.109308 0.01 -0.00924585 0.109611 0.01 -0.00747125 0.111196 0.0126994 -0.00151905 0.113164 0.0155526 -0.00616814 0.109827 0.01 -0.00308534 0.109957 0.01 -0.00149586 0.111437 0.0126994 0.0045555 0.113082 0.0155526 3.08198e-16 0.11 0.01 0.00448598 0.111357 0.0126994 0.00308474 0.109957 0.01 0.0106104 0.112676 0.0155526 0.0104485 0.110956 0.0126994 0.00616737 0.109827 0.01 0.00924536 0.109611 0.01 0.0166197 0.111947 0.0155526 0.012316 0.109308 0.01 0.0163661 0.110239 0.0126994 0.0225581 0.110903 0.0155526 0.0153766 0.10892 0.01 0.0184253 0.108446 0.01 0.0222138 0.109211 0.0126994 0.0284014 0.109552 0.0155526 0.0244771 0.107242 0.01 0.0214598 0.107886 0.01 0.0341265 0.107906 0.0155526 0.0279679 0.107881 0.0126994 0.027475 0.106513 0.01 0.0304516 0.105701 0.01 0.0334044 0.104805 0.01 0.0336057 0.106259 0.0126994 0.0404102 0.107841 0.0185002 0.0347264 0.109803 0.0185002 0.0363304 0.103827 0.01 0.0391061 0.104361 0.0126994 0.039228 0.102768 0.01 0.0451387 0.103783 0.0155526 0.0444498 0.102199 0.0126994 0.0503887 0.101338 0.0155526 0.042095 0.101627 0.01 0.0449288 0.100406 0.01 0.0496197 0.0997913 0.0126994 0.0554468 0.0986612 0.0155526 0.0477269 0.0991067 0.01 0.0504877 0.0977292 0.01 0.0602999 0.0957721 0.0155526 0.0546006 0.0971555 0.0126994 0.0532089 0.0962747 0.01 0.0558881 0.0947445 0.01 0.0593797 0.0943105 0.0126994 0.0649372 0.0926906 0.0155526 0.0585232 0.0931399 0.01 0.0611124 0.0914618 0.01 0.0639461 0.091276 0.0126994 0.0636538 0.0897118 0.01 0.0682917 0.0880719 0.0126994 0.0661447 0.0878913 0.01 0.0685836 0.0860017 0.01 0.0705692 0.0910091 0.0185002 0.0660788 0.09432 0.0185002 0.0709687 0.0840443 0.01 0.0774795 0.0824943 0.0155526 0.0735322 0.0860314 0.0155526 0.0811896 0.0788457 0.0155526 0.0755694 0.0799329 0.01 0.0777815 0.077782 0.01 0.0799505 0.0776423 0.0126994 0.0799325 0.0755698 0.01 0.0833701 0.0739583 0.0126994 0.0826169 0.0802317 0.0185002 0.0861505 0.0764248 0.0185002 0.0820206 0.0732982 0.01 0.0840439 0.0709692 0.01 0.0865573 0.0702015 0.0126994 0.0909021 0.067418 0.0155526 0.0878988 0.0712895 0.0155526 0.0860012 0.0685842 0.01 0.0895148 0.0663891 0.0126994 0.087891 0.066145 0.01 0.0897116 0.063654 0.01 0.0922468 0.0625375 0.0126994 0.0962272 0.0595711 0.0155526 0.0936764 0.0635068 0.0155526 0.0914614 0.061113 0.01 0.0947586 0.0586619 0.0126994 0.0931395 0.0585238 0.01 0.0947443 0.0558884 0.01 0.0970565 0.0547763 0.0126994 0.100293 0.0566031 0.0185002 0.0979188 0.0606183 0.0185002 0.0962744 0.0532093 0.01 0.0991476 0.0508937 0.0126994 0.0977288 0.0504884 0.01 0.0991065 0.0477275 0.01 0.10104 0.0470257 0.0126994 0.100684 0.0516824 0.0155526 0.104409 0.048594 0.0185002 0.102454 0.052591 0.0185002 0.100406 0.0449289 0.01 0.102741 0.043183 0.0126994 0.101627 0.0420955 0.01 0.104259 0.039375 0.0126994 0.102767 0.0392287 0.01 0.107241 0.0361619 0.0155526 0.105875 0.0399852 0.0155526 0.103827 0.0363309 0.01 0.105605 0.03561 0.0126994 0.104805 0.0334045 0.01 0.106785 0.0318955 0.0126994 0.105701 0.0304523 0.01 0.106513 0.0274758 0.01 0.10781 0.0282377 0.0126994 0.109481 0.0286753 0.0155526 0.110373 0.0250239 0.0155526 0.108688 0.024642 0.0126994 0.107242 0.0244774 0.01 0.107886 0.0214601 0.01 0.109429 0.0211131 0.0126994 0.108446 0.0184261 0.01 0.11004 0.0176547 0.0126994 0.10892 0.0153772 0.01 0.11053 0.0142699 0.0126994 0.109308 0.0123162 0.01 0.109611 0.00924585 0.01 0.110907 0.0109611 0.0126994 0.109827 0.00616814 0.01 0.111179 0.00773005 0.0126994 0.114886 0.00798785 0.0185002 0.114605 0.0113266 0.0185002 0.112625 0.011131 0.0155526 0.111353 0.00457808 0.0126994 0.109957 0.00308534 0.01 0.111437 0.00150597 0.0126994 0.11 2.45709e-15 0.01 0.111437 -0.00150597 0.0126994 0.109957 -0.00308534 0.01 0.111353 -0.00457808 0.0126994 0.110907 -0.0109611 0.0126994 0.11004 -0.0176547 0.0126994 0.108446 -0.0184253 0.01 0.109429 -0.0211131 0.0126994 0.109308 -0.012316 0.01 0.105701 -0.0304516 0.01 0.10781 -0.0282377 0.0126994 0.106513 -0.027475 0.01 0.107886 -0.0214598 0.01 0.104259 -0.039375 0.0126994 0.103827 -0.0363304 0.01 0.102768 -0.039228 0.01 0.106785 -0.0318955 0.0126994 0.0977292 -0.0504877 0.01 0.0991476 -0.0508937 0.0126994 0.0991067 -0.0477269 0.01 0.100406 -0.0449288 0.01 0.102741 -0.043183 0.0126994 0.101627 -0.042095 0.01 0.0947445 -0.0558881 0.01 0.0947586 -0.0586619 0.0126994 0.0970565 -0.0547763 0.0126994 0.0962747 -0.0532089 0.01 0.0865573 -0.0702015 0.0126994 0.0895148 -0.0663891 0.0126994 0.0860017 -0.0685836 0.01 0.0897118 -0.0636538 0.01 0.0922468 -0.0625375 0.0126994 0.0914618 -0.0611124 0.01 0.0799329 -0.0755694 0.01 0.0833701 -0.0739583 0.0126994 0.0820207 -0.0732981 0.01 0.0840443 -0.0709687 0.01 0.0709692 -0.0840439 0.01 0.07241 -0.0847184 0.0126994 0.0732982 -0.0820206 0.01 0.0811896 -0.0788457 0.0155526 0.0788415 -0.0839446 0.0185002 0.0826169 -0.0802317 0.0185002 0.061113 -0.0914614 0.01 0.0593797 -0.0943105 0.0126994 0.0639461 -0.091276 0.0126994 0.066145 -0.087891 0.01 0.0682917 -0.0880719 0.0126994 0.0558884 -0.0947443 0.01 0.0532093 -0.0962744 0.01 0.0546006 -0.0971555 0.0126994 0.0554468 -0.0986612 0.0155526 0.0602999 -0.0957721 0.0155526 0.0449289 -0.100406 0.01 0.0420955 -0.101627 0.01 0.0444498 -0.102199 0.0126994 0.0477275 -0.0991065 0.01 0.0496197 -0.0997913 0.0126994 0.0334045 -0.104805 0.01 0.0336057 -0.106259 0.0126994 0.0363309 -0.103827 0.01 0.0391061 -0.104361 0.0126994 0.0392287 -0.102767 0.01 0.0244774 -0.107242 0.01 0.0214601 -0.107886 0.01 0.0222138 -0.109211 0.0126994 0.0304523 -0.105701 0.01 0.0274758 -0.106513 0.01 0.0279679 -0.107881 0.0126994 0.0104485 -0.110956 0.0126994 0.0163661 -0.110239 0.0126994 0.0123162 -0.109308 0.01 0.0184261 -0.108446 0.01 0.00308534 -0.109957 0.01 -3.20632e-16 -0.11 0.01 0.00448598 -0.111357 0.0126994 -0.00151905 -0.113164 0.0155526 0.0045555 -0.113082 0.0155526 -0.00308474 -0.109957 0.01 -0.00616737 -0.109827 0.01 -0.00747125 -0.111196 0.0126994 -0.00149586 -0.111437 0.0126994 -0.0193002 -0.109763 0.0126994 -0.0134144 -0.110637 0.0126994 -0.0153766 -0.10892 0.01 -0.0195993 -0.111464 0.0155526 -0.0136223 -0.112351 0.0155526 -0.0244771 -0.107242 0.01 -0.027475 -0.106513 0.01 -0.025104 -0.108583 0.0126994 -0.0184253 -0.108446 0.01 -0.0214598 -0.107886 0.01 -0.0334044 -0.104805 0.01 -0.0363743 -0.105344 0.0126994 -0.0308027 -0.107106 0.0126994 -0.0304516 -0.105701 0.01 -0.042095 -0.101627 0.01 -0.0417986 -0.103312 0.0126994 -0.039228 -0.102768 0.01 -0.0363304 -0.103827 0.01 -0.0521346 -0.0985007 0.0126994 -0.0470575 -0.101025 0.0126994 -0.0477269 -0.0991067 0.01 -0.0529426 -0.100027 0.0155526 -0.0477868 -0.10259 0.0155526 -0.0570161 -0.0957579 0.0126994 -0.0626461 -0.0942542 0.0155526 -0.0578997 -0.097242 0.0155526 -0.0504877 -0.0977292 0.01 -0.06169 -0.0928157 0.0126994 -0.0585232 -0.0931399 0.01 -0.0611124 -0.0914618 0.01 -0.0558881 -0.0947445 0.01 -0.0768633 -0.0857596 0.0185002 -0.0727267 -0.0892944 0.0185002 -0.0714703 -0.0877518 0.0155526 -0.0671721 -0.091084 0.0155526 -0.0879275 -0.0893882 0.0300502 -0.0941282 -0.0873541 0.0325813 -0.0900532 -0.0915493 0.0325813 -0.0783542 -0.0874231 0.021483 -0.156192 -0.0496245 -0.0352405 -0.15757 -0.0562799 -0.0328772 -0.159464 -0.050664 -0.0328772 -0.0988985 -0.0917811 0.0368012 -0.094617 -0.0961889 0.0368012 -0.0922873 -0.0938205 0.0348514 -0.164083 -0.0802356 0.0124252 -0.16523 -0.0807966 0.00835136 -0.16082 -0.0865891 0.0124252 -0.170848 -0.0681168 -0.00835136 -0.171589 -0.0684123 -0.00419604 -0.17321 -0.0618662 -0.00835136 -0.152856 -0.0823008 0.0270916 -0.155291 -0.0836122 0.0237508 -0.149439 -0.0883536 0.0270916 -0.157225 -0.0929573 0.0124252 -0.161945 -0.0871946 0.00835136 -0.124755 -0.0884689 0.039724 -0.117911 -0.0914492 0.0402139 -0.121719 -0.0863159 0.0402139 -0.141611 -0.100422 0.0270916 -0.143867 -0.102023 0.0237508 -0.137181 -0.106395 0.0270916 -0.0859226 -0.0873501 0.0273172 -0.0817773 -0.0912425 0.0273172 -0.0799963 -0.0892552 0.0244418 -0.116636 -0.0989267 0.039724 -0.109375 -0.101504 0.0402139 -0.113798 -0.0965193 0.0402139 -0.0661447 -0.0878913 0.01 -0.0703795 -0.0864126 0.0126994 -0.066147 -0.0896939 0.0126994 -0.0636538 -0.0897118 0.01 -0.0732981 -0.0820207 0.01 -0.0743826 -0.0829918 0.0126994 -0.0709687 -0.0840443 0.01 -0.0685836 -0.0860017 0.01 -0.0777815 -0.077782 0.01 -0.078153 -0.0794514 0.0126994 -0.0755694 -0.0799329 0.01 -0.0820206 -0.0732982 0.01 -0.0816895 -0.0758106 0.0126994 -0.0799325 -0.0755698 0.01 -0.0860012 -0.0685842 0.01 -0.0849926 -0.0720879 0.0126994 -0.0840439 -0.0709692 0.01 -0.087891 -0.066145 0.01 -0.0880645 -0.0683012 0.0126994 -0.0897116 -0.063654 0.01 -0.0909087 -0.0644673 0.0126994 -0.0935298 -0.0606018 0.0126994 -0.0949794 -0.061541 0.0155526 -0.0931395 -0.0585238 0.01 -0.0959339 -0.0567195 0.0126994 -0.0914614 -0.061113 0.01 -0.0962744 -0.0532093 0.01 -0.0981274 -0.0528339 0.0126994 -0.0974207 -0.0575986 0.0155526 -0.0996482 -0.0536527 0.0155526 -0.1014 -0.0545959 0.0185002 -0.10167 -0.0497159 0.0155526 -0.100118 -0.0489572 0.0126994 -0.0977288 -0.0504884 0.01 -0.0991065 -0.0477275 0.01 -0.101913 -0.0451006 0.0126994 -0.106975 -0.0426506 0.0185002 -0.105127 -0.0419138 0.0155526 -0.108453 -0.0387368 0.0185002 -0.100406 -0.0449289 0.01 -0.101627 -0.0420955 0.01 -0.103522 -0.0412741 0.0126994 -0.102767 -0.0392287 0.01 -0.104953 -0.0374866 0.0126994 -0.106215 -0.033746 0.0126994 -0.103827 -0.0363309 0.01 -0.104805 -0.0334045 0.01 -0.107317 -0.0300591 0.0126994 -0.105701 -0.0304523 0.01 -0.107861 -0.034269 0.0155526 -0.110896 -0.0310616 0.0185002 -0.109757 -0.0348715 0.0185002 -0.106513 -0.0274758 0.01 -0.108267 -0.0264318 0.0126994 -0.109945 -0.0268414 0.0155526 -0.110766 -0.0232234 0.0155526 -0.112713 -0.0236317 0.0185002 -0.107242 -0.0244774 0.01 -0.10975 -0.0193749 0.0126994 -0.109075 -0.022869 0.0126994 -0.107886 -0.0214601 0.01 -0.108446 -0.0184261 0.01 -0.111451 -0.0196752 0.0155526 -0.110299 -0.015953 0.0126994 -0.10892 -0.0153772 0.01 -0.110732 -0.0126059 0.0126994 -0.109308 -0.0123162 0.01 -0.116644 -0.013279 0.021483 -0.114425 -0.0130263 0.0185002 -0.116985 -0.00983423 0.021483 -0.109611 -0.00924585 0.01 -0.111055 -0.00933575 0.0126994 -0.109827 -0.00616814 0.01 -0.117354 -0.0031939 0.021483 -0.118435 0 0.0227693 -0.119813 -0.00326083 0.0244418 -0.109957 -0.00308534 0.01 -0.111277 -0.00614412 0.0126994 -0.111406 -0.00303201 0.0126994 -0.111448 0 0.0127028 -0.113032 0 0.0153293 -0.0947443 -0.0558884 0.01 -0.0923176 -0.0654664 0.0155526 -0.0939405 -0.0666173 0.0185002 -0.0894293 -0.0693597 0.0155526 -0.0829555 -0.0769855 0.0155526 -0.0863099 -0.0732051 0.0155526 -0.0793642 -0.0806827 0.0155526 -0.0755354 -0.084278 0.0155526 -0.0756911 -0.0929341 0.0244418 -0.0773763 -0.0950033 0.0273172 -0.104016 -0.0965303 0.0395028 -0.10142 -0.0941215 0.0383714 -0.108222 -0.0917902 0.0395028 -0.0970298 -0.0986418 0.0383714 -0.133684 -0.094801 0.0352405 -0.137538 -0.0891168 0.0352405 -0.14042 -0.0909836 0.0328772 -0.120852 -0.0937302 0.039724 -0.127784 -0.0906172 0.0387046 -0.136484 -0.0967869 0.0328772 -0.14315 -0.0927528 0.0301473 -0.123786 -0.0960064 0.0387046 -0.130772 -0.0927362 0.0371966 -0.153936 -0.0910126 0.0201657 -0.148016 -0.0959054 0.0237508 -0.15182 -0.0897614 0.0237508 -0.146829 -0.0868108 0.0301473 -0.144029 -0.0851549 0.0328772 -0.162543 -0.0794828 0.0163769 -0.157456 -0.0847776 0.0201657 -0.16065 -0.078557 0.0201657 -0.159312 -0.0857767 0.0163769 -0.169175 -0.0748662 3.45529e-17 -0.168923 -0.0747547 -0.00419604 -0.168923 -0.0747547 0.00419604 -0.171845 -0.0685143 3.31663e-17 -0.134543 -0.0871758 0.0371966 -0.168193 -0.0744319 0.00835136 -0.171589 -0.0684123 0.00419604 -0.167025 -0.073915 -0.0124252 -0.164083 -0.0802356 -0.0124252 -0.16523 -0.0807966 -0.00835136 -0.172007 -0.0614366 -0.0124252 -0.169662 -0.0676438 -0.0124252 -0.168409 -0.0601513 -0.0201657 -0.166113 -0.0662287 -0.0201657 -0.16807 -0.0670092 -0.0163769 -0.170393 -0.0608602 -0.0163769 -0.172442 -0.0547872 -0.0163769 -0.110985 -0.094134 0.0401362 -0.129501 -0.100439 0.0352405 -0.122262 -0.103699 0.0371966 -0.126681 -0.0982514 0.0371966 -0.170433 -0.0541491 -0.0201657 -0.166094 -0.0593244 -0.0237508 -0.16809 -0.0534047 -0.0237508 -0.114997 -0.0891893 0.0401362 -0.16717 -0.0468239 -0.0270916 -0.165454 -0.0525671 -0.0270916 -0.106672 -0.0989952 0.0401362 -0.164251 -0.0460063 -0.0301473 -0.162565 -0.0516492 -0.0301473 -0.165706 -0.0404546 -0.0301473 -0.162545 -0.0396829 -0.0328772 -0.0964634 -0.0895212 0.0348514 -0.102897 -0.0872742 0.0368012 -0.155742 -0.0380221 -0.0371966 -0.156905 -0.032897 -0.0371966 -0.15332 -0.0321454 -0.0387046 -0.15921 -0.0388687 -0.0352405 -0.161118 -0.0451288 -0.0328772 -0.149685 -0.0313832 -0.039724 -0.152184 -0.0371533 -0.0387046 -0.142212 -0.0451829 -0.0402139 -0.143687 -0.0402465 -0.0402139 -0.140137 -0.0392519 -0.0401362 -0.143314 -0.0253002 -0.0401362 -0.146042 -0.0306195 -0.0402139 -0.146945 -0.0259413 -0.0402139 -0.142433 -0.0298628 -0.0401362 -0.139746 -0.0246702 -0.0395028 -0.119499 -0.0379666 -0.0300502 -0.117986 -0.0330474 -0.0273172 -0.116774 -0.0371009 -0.0273172 -0.13694 -0.0198062 -0.0383714 -0.140445 -0.0203131 -0.0395028 -0.137477 -0.0156507 -0.0383714 -0.127593 -0.0145254 -0.0325813 -0.130758 -0.0148857 -0.0348514 -0.127965 -0.0107573 -0.0325813 -0.130247 -0.0188381 -0.0348514 -0.133535 -0.0193137 -0.0368012 -0.122096 -0.0102639 -0.0273172 -0.12174 -0.0138591 -0.0273172 -0.124581 -0.0141825 -0.0300502 -0.124945 -0.0105034 -0.0300502 -0.118435 0 -0.0227696 -0.117354 -0.0031939 -0.021483 -0.119813 -0.00326083 -0.0244418 -0.119437 -0.0100403 -0.0244418 -0.114425 -0.0130263 -0.0185002 -0.114759 -0.0096471 -0.0185002 -0.112776 -0.00948044 -0.0155526 -0.115121 -0.00313313 -0.0185002 -0.116532 0 -0.0203643 -0.109827 -0.00616737 -0.01 -0.111277 -0.00614412 -0.0126994 -0.109957 -0.00308534 -0.01 -0.113002 -0.00623934 -0.0155526 -0.113132 -0.003079 -0.0155526 -0.111406 -0.00303201 -0.0126994 -0.0532089 -0.0962747 0.01 -0.134059 -0.0152615 -0.0368012 -0.148576 -0.0362725 -0.039724 -0.157812 -0.0442028 -0.0352405 -0.087835 -0.0980012 0.0348514 -0.0857087 -0.0956289 0.0325813 -0.0836855 -0.0933715 0.0300502 -0.0791818 -0.09722 0.0300502 0.00924585 -0.109611 0.01 0.00616814 -0.109827 0.01 -0.0449288 -0.100406 0.01 -0.0375874 -0.108857 0.0185002 -0.03183 -0.110678 0.0185002 -0.0312801 -0.108766 0.0155526 -0.0424464 -0.104913 0.0155526 -0.0254931 -0.110266 0.0155526 -0.00924536 -0.109611 0.01 -0.012316 -0.109308 0.01 -0.00758704 -0.11292 0.0155526 0.0153772 -0.10892 0.01 0.0106104 -0.112676 0.0155526 0.0166197 -0.111947 0.0155526 0.0229547 -0.112853 0.0185002 0.0289007 -0.111478 0.0185002 0.0284014 -0.109552 0.0155526 0.0341265 -0.107906 0.0155526 0.0397121 -0.105978 0.0155526 0.0451387 -0.103783 0.0155526 0.0564216 -0.100396 0.0185002 0.0512745 -0.103119 0.0185002 0.0504884 -0.0977288 0.01 0.0585238 -0.0931395 0.01 0.063654 -0.0897116 0.01 0.077782 -0.0777815 0.01 0.0799505 -0.0776423 0.0126994 0.0649372 -0.0926906 0.0155526 0.0685842 -0.0860012 0.01 0.076297 -0.0812353 0.0126994 0.0755698 -0.0799325 0.01 0.0693501 -0.0894369 0.0155526 0.0735322 -0.0860314 0.0155526 0.0878988 -0.0712895 0.0155526 0.0861505 -0.0764248 0.0185002 0.089444 -0.0725427 0.0185002 0.0878913 -0.0661447 0.01 0.0936764 -0.0635068 0.0155526 0.0909021 -0.067418 0.0155526 0.0931399 -0.0585232 0.01 0.0962272 -0.0595711 0.0155526 0.0985607 -0.0556253 0.0155526 0.10104 -0.0470257 0.0126994 0.105875 -0.0399852 0.0155526 0.104333 -0.0438522 0.0155526 0.105605 -0.03561 0.0126994 0.104805 -0.0334044 0.01 0.108688 -0.024642 0.0126994 0.11053 -0.0142699 0.0126994 0.107242 -0.0244771 0.01 0.10892 -0.0153766 0.01 -0.11473 0 0.0178831 -0.113132 -0.003079 0.0155526 -0.124739 0 0.029462 -0.122481 -0.00333343 0.0273172 -0.122537 0 0.0273276 -0.115121 -0.00313313 0.0185002 -0.113002 -0.00623934 0.0155526 -0.112776 -0.00948044 0.0155526 -0.112448 -0.0128012 0.0155526 -0.112009 -0.0162002 0.0155526 -0.119089 -0.0135572 0.0244418 -0.118623 -0.0171569 0.0244418 -0.116189 -0.0168048 0.021483 -0.10898 -0.030525 0.0155526 -0.10658 -0.0380676 0.0155526 -0.103493 -0.0457995 0.0155526 -0.105312 -0.0466047 0.0185002 -0.10905 -0.0434779 0.021483 -0.107355 -0.0475087 0.021483 -0.0966491 -0.0626229 0.0185002 -0.0991333 -0.0586111 0.0185002 -0.101056 -0.059748 0.021483 -0.0878271 -0.0744921 0.0185002 -0.0927667 -0.0719481 0.021483 -0.0895308 -0.075937 0.021483 -0.0844138 -0.0783388 0.0185002 -0.0807594 -0.0821011 0.0185002 -0.0637474 -0.0959111 0.0185002 -0.0589176 -0.0989515 0.0185002 -0.0538733 -0.101786 0.0185002 -0.0486269 -0.104394 0.0185002 -0.0440305 -0.108828 0.021483 -0.0383165 -0.110969 0.021483 -0.036938 -0.106976 0.0155526 -0.0259413 -0.112204 0.0185002 -0.0199439 -0.113424 0.0185002 -0.0138618 -0.114326 0.0185002 -0.00772041 -0.114905 0.0185002 -0.00154575 -0.115153 0.0185002 0.00463558 -0.11507 0.0185002 0.0107969 -0.114656 0.0185002 0.0172399 -0.116125 0.021483 0.0233999 -0.115042 0.021483 0.0225581 -0.110903 0.0155526 0.0347264 -0.109803 0.0185002 0.0404102 -0.107841 0.0185002 0.0459322 -0.105607 0.0185002 0.0503887 -0.101338 0.0155526 0.06136 -0.0974558 0.0185002 0.0705692 -0.0910091 0.0185002 0.0673605 -0.0961496 0.021483 0.0719381 -0.0927745 0.021483 0.0748249 -0.0875438 0.0185002 0.0774795 -0.0824943 0.0155526 0.0846622 -0.0751045 0.0155526 0.0925001 -0.0686032 0.0185002 0.0953232 -0.0646232 0.0185002 0.102454 -0.052591 0.0185002 0.102239 -0.0577011 0.021483 0.104442 -0.0536111 0.021483 0.100684 -0.0516824 0.0155526 0.102606 -0.0477545 0.0155526 0.106167 -0.0446231 0.0185002 0.107736 -0.0406881 0.0185002 0.107241 -0.0361619 0.0155526 0.10844 -0.0323898 0.0155526 0.109481 -0.0286753 0.0155526 0.110373 -0.0250239 0.0155526 0.111125 -0.0214403 0.0155526 0.111745 -0.0179283 0.0155526 0.112243 -0.0144911 0.0155526 0.112625 -0.011131 0.0155526 0.112902 -0.00784985 0.0155526 0.113079 -0.00464903 0.0155526 0.113164 -0.00152931 0.0155526 0.113164 0.00152931 0.0155526 0.113079 0.00464903 0.0155526 0.112902 0.00784985 0.0155526 0.112243 0.0144911 0.0155526 0.111745 0.0179283 0.0155526 0.111125 0.0214403 0.0155526 0.112313 0.0254638 0.0185002 0.111406 0.0291794 0.0185002 0.10844 0.0323898 0.0155526 0.109127 0.0367976 0.0185002 0.107736 0.0406881 0.0185002 0.104333 0.0438522 0.0155526 0.102606 0.0477545 0.0155526 0.0985607 0.0556253 0.0155526 0.0925001 0.0686032 0.0185002 0.0971723 0.0658767 0.021483 0.0942944 0.0699339 0.021483 0.089444 0.0725427 0.0185002 0.0846622 0.0751045 0.0155526 0.0788415 0.0839446 0.0185002 0.0748249 0.0875438 0.0185002 0.0693501 0.0894369 0.0155526 0.06136 0.0974558 0.0185002 0.0564216 0.100396 0.0185002 0.0512745 0.103119 0.0185002 0.0468232 0.107656 0.021483 0.0411941 0.109933 0.021483 0.0397121 0.105978 0.0155526 0.0289007 0.111478 0.0185002 0.0229547 0.112853 0.0185002 0.0169119 0.113915 0.0185002 0.0107969 0.114656 0.0185002 0.00463558 0.11507 0.0185002 -0.00154575 0.115153 0.0185002 -0.00772041 0.114905 0.0185002 -0.0138618 0.114326 0.0185002 -0.0203307 0.115624 0.021483 -0.0264445 0.11438 0.021483 -0.0259413 0.112204 0.0185002 -0.03183 0.110678 0.0185002 -0.0529426 0.100027 0.0155526 -0.0578997 0.097242 0.0155526 -0.0626461 0.0942542 0.0155526 -0.0671721 0.091084 0.0155526 -0.0714703 0.0877518 0.0155526 -0.0755354 0.084278 0.0155526 -0.0793642 0.0806827 0.0155526 -0.0829555 0.0769855 0.0155526 -0.0863099 0.0732051 0.0155526 -0.0894293 0.0693597 0.0155526 -0.0923176 0.0654664 0.0155526 -0.0768633 0.0857596 0.0185002 -0.0807594 0.0821011 0.0185002 -0.0974207 0.0575986 0.0155526 -0.0949794 0.061541 0.0155526 -0.0996482 0.0536527 0.0155526 -0.10167 0.0497159 0.0155526 -0.103493 0.0457995 0.0155526 -0.105127 0.0419138 0.0155526 -0.0991333 0.0586111 0.0185002 -0.10658 0.0380676 0.0155526 -0.107861 0.034269 0.0155526 -0.10898 0.030525 0.0155526 -0.109945 0.0268414 0.0155526 -0.109757 0.0348715 0.0185002 -0.108453 0.0387368 0.0185002 -0.111451 0.0196752 0.0155526 -0.112009 0.0162002 0.0155526 -0.112448 0.0128012 0.0155526 -0.11341 0.0200211 0.0185002 -0.112776 0.00948044 0.0155526 -0.113132 0.003079 0.0155526 -0.116532 0 0.0203642 -0.114989 -0.00634903 0.0185002 -0.114759 -0.0096471 0.0185002 -0.113978 -0.016485 0.0185002 -0.11341 -0.0200211 0.0185002 -0.118033 -0.0208371 0.0244418 -0.120661 -0.0213011 0.0273172 -0.117307 -0.0245949 0.0244418 -0.111878 -0.0273133 0.0185002 -0.113047 -0.0316641 0.021483 -0.114048 -0.0278431 0.021483 -0.116438 -0.0284266 0.0244418 -0.112874 -0.0403157 0.0244418 -0.110557 -0.0394882 0.021483 -0.114231 -0.0362928 0.0244418 -0.103457 -0.0505899 0.0185002 -0.103367 -0.0556549 0.021483 -0.105464 -0.0515712 0.021483 -0.107674 -0.052652 0.0244418 -0.0985238 -0.0638376 0.021483 -0.100589 -0.0651754 0.0244418 -0.0957627 -0.0679095 0.021483 -0.0910015 -0.0705791 0.0185002 -0.0860513 -0.0798584 0.021483 -0.091407 -0.0775284 0.0244418 -0.0878546 -0.081532 0.0244418 -0.0823259 -0.0836937 0.021483 -0.064984 -0.0977715 0.021483 -0.0600604 -0.100871 0.021483 -0.0549184 -0.10376 0.021483 -0.0506089 -0.108649 0.0244418 -0.0449532 -0.111109 0.0244418 -0.0431926 -0.106757 0.0185002 -0.0324474 -0.112824 0.021483 -0.0264445 -0.11438 0.021483 -0.0203307 -0.115624 0.021483 -0.0141307 -0.116544 0.021483 -0.00787017 -0.117133 0.021483 -0.00157574 -0.117387 0.021483 0.0047255 -0.117302 0.021483 0.011237 -0.11933 0.0244418 0.0176012 -0.118558 0.0244418 0.0169119 -0.113915 0.0185002 0.0294613 -0.113641 0.021483 0.0354 -0.111933 0.021483 0.0411941 -0.109933 0.021483 0.0478044 -0.109912 0.0244418 0.0533645 -0.107323 0.0244418 0.0522691 -0.10512 0.021483 0.057516 -0.102343 0.021483 0.0625502 -0.0993462 0.021483 0.0660788 -0.09432 0.0185002 0.0762763 -0.0892419 0.021483 0.0803708 -0.0855729 0.021483 0.0842194 -0.081788 0.021483 0.0878216 -0.0779073 0.021483 0.091179 -0.0739499 0.021483 0.0942944 -0.0699339 0.021483 0.0971723 -0.0658767 0.021483 0.0979188 -0.0606183 0.0185002 0.100293 -0.0566031 0.0185002 0.104409 -0.048594 0.0185002 0.111243 -0.0375114 0.021483 0.112128 -0.0423466 0.0244418 0.113575 -0.0382975 0.0244418 0.109127 -0.0367976 0.0185002 0.110347 -0.0329592 0.0185002 0.111406 -0.0291794 0.0185002 0.112313 -0.0254638 0.0185002 0.113078 -0.0218172 0.0185002 0.113709 -0.0182435 0.0185002 0.114216 -0.0147458 0.0185002 0.114605 -0.0113266 0.0185002 0.114886 -0.00798785 0.0185002 0.115066 -0.00473076 0.0185002 0.115153 -0.00155619 0.0185002 0.115153 0.00155619 0.0185002 0.115066 0.00473076 0.0185002 0.116431 0.0150319 0.021483 0.119277 0.0117883 0.0244418 0.118871 0.0153469 0.0244418 0.114216 0.0147458 0.0185002 0.113709 0.0182435 0.0185002 0.113078 0.0218172 0.0185002 0.112487 0.0335985 0.021483 0.115947 0.0303688 0.0244418 0.114844 0.0343026 0.0244418 0.110347 0.0329592 0.0185002 0.112128 0.0423466 0.0244418 0.110495 0.046442 0.0244418 0.108226 0.0454887 0.021483 0.106167 0.0446231 0.0185002 0.106435 0.0495366 0.021483 0.104442 0.0536111 0.021483 0.102239 0.0577011 0.021483 0.0998182 0.0617941 0.021483 0.0953232 0.0646232 0.0185002 0.091179 0.0739499 0.021483 0.0878216 0.0779073 0.021483 0.0842194 0.081788 0.021483 0.0803708 0.0855729 0.021483 0.0778748 0.0911121 0.0244418 0.0734456 0.0947187 0.0244418 0.0719381 0.0927745 0.021483 0.0673605 0.0961496 0.021483 0.0625502 0.0993462 0.021483 0.057516 0.102343 0.021483 0.0522691 0.10512 0.021483 0.0459322 0.105607 0.0185002 0.0354 0.111933 0.021483 0.0294613 0.113641 0.021483 0.0233999 0.115042 0.021483 0.0172399 0.116125 0.021483 0.0110064 0.11688 0.021483 0.0047255 0.117302 0.021483 -0.00157574 0.117387 0.021483 -0.00787017 0.117133 0.021483 -0.0144268 0.118986 0.0244418 -0.0207568 0.118047 0.0244418 -0.0199439 0.113424 0.0185002 -0.0324474 0.112824 0.021483 -0.0383165 0.110969 0.021483 -0.0538733 0.101786 0.0185002 -0.0589176 0.0989515 0.0185002 -0.0637474 0.0959111 0.0185002 -0.068353 0.0926852 0.0185002 -0.0727267 0.0892944 0.0185002 -0.105227 0.0681812 0.0300502 -0.107932 0.0638133 0.0300502 -0.105471 0.0623583 0.0273172 -0.0844138 0.0783388 0.0185002 -0.0878271 0.0744921 0.0185002 -0.0910015 0.0705791 0.0185002 -0.0939405 0.0666173 0.0185002 -0.0783542 0.0874231 0.021483 -0.0966491 0.0626229 0.0185002 -0.1014 0.0545959 0.0185002 -0.103457 0.0505899 0.0185002 -0.105312 0.0466047 0.0185002 -0.106975 0.0426506 0.0185002 -0.101056 0.059748 0.021483 -0.110896 0.0310616 0.0185002 -0.111878 0.0273133 0.0185002 -0.111886 0.0355479 0.021483 -0.110557 0.0394882 0.021483 -0.112713 0.0236317 0.0185002 -0.113978 0.016485 0.0185002 -0.114425 0.0130263 0.0185002 -0.114759 0.0096471 0.0185002 -0.116644 0.013279 0.021483 -0.116985 0.00983423 0.021483 -0.115121 0.00313313 0.0185002 -0.114989 0.00634903 0.0185002 -0.13464 0 0.03665 -0.134875 -0.00367074 0.0368012 -0.131993 0 0.0351024 -0.117219 -0.00647218 0.021483 -0.128369 -0.00349369 0.0325813 -0.129463 0 0.0333698 -0.131554 -0.00358036 0.0348514 -0.11561 -0.0204094 0.021483 -0.114899 -0.02409 0.021483 -0.111886 -0.0355479 0.021483 -0.111335 -0.044389 0.0244418 -0.115387 -0.0412134 0.0273172 -0.113814 -0.0453774 0.0273172 -0.103174 -0.0610002 0.0244418 -0.105533 -0.0568212 0.0244418 -0.107883 -0.0580864 0.0273172 -0.0977695 -0.0693326 0.0244418 -0.0840512 -0.0854476 0.0244418 -0.0898107 -0.0833473 0.0273172 -0.0711391 -0.0964631 0.0244418 -0.0663458 -0.0998205 0.0244418 -0.0613191 -0.102985 0.0244418 -0.0573176 -0.108293 0.0273172 -0.0517357 -0.111068 0.0273172 -0.0495701 -0.106419 0.021483 -0.0391195 -0.113294 0.0244418 -0.0331274 -0.115189 0.0244418 -0.0269987 -0.116777 0.0244418 -0.0207568 -0.118047 0.0244418 -0.0144268 -0.118986 0.0244418 -0.0080351 -0.119588 0.0244418 -0.00160876 -0.119847 0.0244418 0.00493195 -0.122427 0.0273172 0.0114872 -0.121987 0.0273172 0.0110064 -0.11688 0.021483 0.0238903 -0.117453 0.0244418 0.0300787 -0.116022 0.0244418 0.0361419 -0.114279 0.0244418 0.0420574 -0.112237 0.0244418 0.0468232 -0.107656 0.021483 0.0587213 -0.104488 0.0244418 0.063861 -0.101428 0.0244418 0.0687722 -0.0981646 0.0244418 0.0734456 -0.0947187 0.0244418 0.0778748 -0.0911121 0.0244418 0.0820551 -0.0873662 0.0244418 0.0859843 -0.083502 0.0244418 0.0896621 -0.07954 0.0244418 0.0930898 -0.0754996 0.0244418 0.0962705 -0.0713995 0.0244418 0.0992086 -0.0672572 0.0244418 0.0998182 -0.0617941 0.021483 0.104381 -0.0589103 0.0244418 0.10663 -0.0547346 0.0244418 0.106435 -0.0495366 0.021483 0.108226 -0.0454887 0.021483 0.109826 -0.0414774 0.021483 0.112487 -0.0335985 0.021483 0.113567 -0.0297454 0.021483 0.114492 -0.0259578 0.021483 0.115272 -0.0222404 0.021483 0.115915 -0.0185974 0.021483 0.116431 -0.0150319 0.021483 0.116828 -0.0115463 0.021483 0.117115 -0.00814279 0.021483 0.117298 -0.00482252 0.021483 0.117387 -0.00158638 0.021483 0.117387 0.00158638 0.021483 0.117298 0.00482252 0.021483 0.117115 0.00814279 0.021483 0.116828 0.0115463 0.021483 0.115915 0.0185974 0.021483 0.115272 0.0222404 0.021483 0.114492 0.0259578 0.021483 0.113567 0.0297454 0.021483 0.111243 0.0375114 0.021483 0.109826 0.0414774 0.021483 0.108665 0.0505747 0.0244418 0.10663 0.0547346 0.0244418 0.104381 0.0589103 0.0244418 0.10191 0.0630891 0.0244418 0.0992086 0.0672572 0.0244418 0.0962705 0.0713995 0.0244418 0.0930898 0.0754996 0.0244418 0.0896621 0.07954 0.0244418 0.0859843 0.083502 0.0244418 0.0820551 0.0873662 0.0244418 0.0762763 0.0892419 0.021483 0.0687722 0.0981646 0.0244418 0.063861 0.101428 0.0244418 0.0587213 0.104488 0.0244418 0.0545527 0.109712 0.0273172 0.0488688 0.112359 0.0273172 0.0478044 0.109912 0.0244418 0.0420574 0.112237 0.0244418 0.0361419 0.114279 0.0244418 0.0300787 0.116022 0.0244418 0.0238903 0.117453 0.0244418 0.0176012 0.118558 0.0244418 0.011237 0.11933 0.0244418 0.00482453 0.119761 0.0244418 -0.00160876 0.119847 0.0244418 -0.008214 0.122251 0.0273172 -0.014748 0.121636 0.0273172 -0.0141307 0.116544 0.021483 -0.0269987 0.116777 0.0244418 -0.0331274 0.115189 0.0244418 -0.0391195 0.113294 0.0244418 -0.045954 0.113582 0.0273172 -0.0600604 0.100871 0.021483 -0.064984 0.0977715 0.021483 -0.0696789 0.094483 0.021483 -0.0741374 0.0910265 0.021483 -0.0449532 0.111109 0.0244418 -0.0860513 0.0798584 0.021483 -0.0895308 0.075937 0.021483 -0.0927667 0.0719481 0.021483 -0.0957627 0.0679095 0.021483 -0.107674 0.052652 0.0244418 -0.105464 0.0515712 0.021483 -0.105533 0.0568212 0.0244418 -0.0985238 0.0638376 0.021483 -0.103367 0.0556549 0.021483 -0.107355 0.0475087 0.021483 -0.10905 0.0434779 0.021483 -0.103174 0.0610002 0.0244418 -0.113047 0.0316641 0.021483 -0.114048 0.0278431 0.021483 -0.114899 0.02409 0.021483 -0.11561 0.0204094 0.021483 -0.116189 0.0168048 0.021483 -0.118033 0.0208371 0.0244418 -0.119089 0.0135572 0.0244418 -0.119437 0.0100403 0.0244418 -0.117354 0.0031939 0.021483 -0.117219 0.00647218 0.021483 -0.120436 0 0.0250932 -0.119676 -0.00660782 0.0244418 -0.119437 -0.0100403 0.0244418 -0.124581 -0.0141825 0.0300502 -0.127965 -0.0107573 0.0325813 -0.127593 -0.0145254 0.0325813 -0.125684 -0.0263512 0.0325813 -0.121808 -0.0297375 0.0300502 -0.122717 -0.0257292 0.0300502 -0.115416 -0.0323277 0.0244418 -0.119499 -0.0379666 0.0300502 -0.116774 -0.0371009 0.0273172 -0.120739 -0.0338186 0.0300502 -0.109605 -0.0485043 0.0244418 -0.112045 -0.0495842 0.0273172 -0.11647 -0.0464362 0.0300502 -0.11466 -0.0507412 0.0300502 -0.105471 -0.0623583 0.0273172 -0.102828 -0.0666266 0.0273172 -0.105227 -0.0681812 0.0300502 -0.0999463 -0.0708763 0.0273172 -0.0947107 -0.0734559 0.0244418 -0.0968195 -0.0750914 0.0273172 -0.0934422 -0.0792545 0.0273172 -0.072723 -0.0986108 0.0273172 -0.067823 -0.102043 0.0273172 -0.0626843 -0.105278 0.0273172 -0.0560692 -0.105935 0.0244418 -0.045954 -0.113582 0.0273172 -0.0399904 -0.115817 0.0273172 -0.033865 -0.117753 0.0273172 -0.0275998 -0.119377 0.0273172 -0.0212189 -0.120675 0.0273172 -0.014748 -0.121636 0.0273172 -0.008214 -0.122251 0.0273172 -0.00168295 -0.125374 0.0300502 0.00504703 -0.125284 0.0300502 0.00482453 -0.119761 0.0244418 0.0179931 -0.121198 0.0273172 0.0244222 -0.120068 0.0273172 0.0307484 -0.118605 0.0273172 0.0369466 -0.116823 0.0273172 0.043997 -0.117413 0.0300502 0.0500091 -0.114981 0.0300502 0.0488688 -0.112359 0.0273172 0.0545527 -0.109712 0.0273172 0.0600287 -0.106814 0.0273172 0.0668062 -0.106106 0.0300502 0.0719438 -0.102692 0.0300502 0.0703034 -0.10035 0.0273172 0.0750809 -0.0968276 0.0273172 0.0814662 -0.095314 0.0300502 0.0858393 -0.0913953 0.0300502 0.0838821 -0.0893114 0.0273172 0.0878988 -0.0853612 0.0273172 0.0916584 -0.0813109 0.0273172 0.0951624 -0.0771806 0.0273172 0.104179 -0.0644938 0.0273172 0.103784 -0.070359 0.0300502 0.10661 -0.0659987 0.0300502 0.10191 -0.0630891 0.0244418 0.106705 -0.0602219 0.0273172 0.109004 -0.0559533 0.0273172 0.108665 -0.0505747 0.0244418 0.110495 -0.046442 0.0244418 0.114624 -0.0432894 0.0273172 0.116103 -0.0391502 0.0273172 0.114844 -0.0343026 0.0244418 0.115947 -0.0303688 0.0244418 0.116891 -0.0265018 0.0244418 0.117687 -0.0227065 0.0244418 0.118344 -0.0189871 0.0244418 0.118871 -0.0153469 0.0244418 0.119277 -0.0117883 0.0244418 0.119569 -0.00831344 0.0244418 0.119757 -0.00492358 0.0244418 0.119847 -0.00161963 0.0244418 0.119847 0.00161963 0.0244418 0.119757 0.00492358 0.0244418 0.119569 0.00831344 0.0244418 0.120979 0.0194099 0.0273172 0.124353 0.0160546 0.0300502 0.123802 0.0198628 0.0300502 0.118344 0.0189871 0.0244418 0.117687 0.0227065 0.0244418 0.116891 0.0265018 0.0244418 0.118528 0.0310449 0.0273172 0.117401 0.0350664 0.0273172 0.113575 0.0382975 0.0244418 0.114624 0.0432894 0.0273172 0.112955 0.047476 0.0273172 0.111084 0.0517008 0.0273172 0.109004 0.0559533 0.0273172 0.106705 0.0602219 0.0273172 0.104179 0.0644938 0.0273172 0.101418 0.0687547 0.0273172 0.0984139 0.0729892 0.0273172 0.0973829 0.0789815 0.0300502 0.0937971 0.0832082 0.0300502 0.0916584 0.0813109 0.0273172 0.0878988 0.0853612 0.0273172 0.0858393 0.0913953 0.0300502 0.0814662 0.095314 0.0300502 0.0796086 0.0931407 0.0273172 0.0750809 0.0968276 0.0273172 0.0703034 0.10035 0.0273172 0.0652829 0.103686 0.0273172 0.0614294 0.109307 0.0300502 0.0558256 0.112272 0.0300502 0.0533645 0.107323 0.0244418 0.0429938 0.114736 0.0273172 0.0369466 0.116823 0.0273172 0.0307484 0.118605 0.0273172 0.0244222 0.120068 0.0273172 0.0179931 0.121198 0.0273172 0.0114872 0.121987 0.0273172 0.00504703 0.125284 0.0300502 -0.00168295 0.125374 0.0300502 -0.00164458 0.122515 0.0273172 -0.00840566 0.125103 0.0300502 -0.0080351 0.119588 0.0244418 -0.0212189 0.120675 0.0273172 -0.0275998 0.119377 0.0273172 -0.033865 0.117753 0.0273172 -0.0399904 0.115817 0.0273172 -0.0663458 0.0998205 0.0244418 -0.0711391 0.0964631 0.0244418 -0.0756911 0.0929341 0.0244418 -0.0878546 0.081532 0.0244418 -0.091407 0.0775284 0.0244418 -0.0947107 0.0734559 0.0244418 -0.0977695 0.0693326 0.0244418 -0.0859226 0.0873501 0.0273172 -0.0817773 0.0912425 0.0273172 -0.100589 0.0651754 0.0244418 -0.109605 0.0485043 0.0244418 -0.111335 0.044389 0.0244418 -0.112874 0.0403157 0.0244418 -0.114231 0.0362928 0.0244418 -0.115416 0.0323277 0.0244418 -0.116438 0.0284266 0.0244418 -0.115387 0.0412134 0.0273172 -0.116774 0.0371009 0.0273172 -0.117307 0.0245949 0.0244418 -0.118623 0.0171569 0.0244418 -0.120661 0.0213011 0.0273172 -0.12174 0.0138591 0.0273172 -0.122096 0.0102639 0.0273172 -0.119813 0.00326083 0.0244418 -0.119676 0.00660782 0.0244418 -0.125339 -0.00341122 0.0300502 -0.12234 -0.00675494 0.0273172 -0.122096 -0.0102639 0.0273172 -0.12174 -0.0138591 0.0273172 -0.121265 -0.0175389 0.0273172 -0.130758 -0.0148857 0.0348514 -0.130247 -0.0188381 0.0348514 -0.127094 -0.0183821 0.0325813 -0.119919 -0.0251425 0.0273172 -0.119031 -0.0290595 0.0273172 -0.117986 -0.0330474 0.0273172 -0.120934 -0.0431947 0.0325813 -0.118079 -0.042175 0.0300502 -0.122388 -0.0388845 0.0325813 -0.110071 -0.0538242 0.0273172 -0.11264 -0.0550802 0.0300502 -0.107932 -0.0638133 0.0300502 -0.1104 -0.0594417 0.0300502 -0.113069 -0.0608788 0.0325813 -0.102278 -0.0725301 0.0300502 -0.104751 -0.0742836 0.0325813 -0.0990786 -0.0768435 0.0300502 -0.0919063 -0.0852921 0.0300502 -0.0979343 -0.0830646 0.0325813 -0.0744199 -0.100912 0.0300502 -0.0694055 -0.104424 0.0300502 -0.0656978 -0.110339 0.0325813 -0.0600731 -0.113499 0.0325813 -0.058655 -0.11082 0.0300502 -0.0529429 -0.11366 0.0300502 -0.0470263 -0.116233 0.0300502 -0.0409236 -0.118519 0.0300502 -0.0346551 -0.120501 0.0300502 -0.0282438 -0.122163 0.0300502 -0.021714 -0.123491 0.0300502 -0.015457 -0.127483 0.0325813 -0.00860888 -0.128128 0.0325813 -0.00840566 -0.125103 0.0300502 -0.00172364 -0.128405 0.0325813 -0.00164458 -0.122515 0.0273172 0.0117552 -0.124833 0.0300502 0.0184129 -0.124026 0.0300502 0.0249921 -0.122869 0.0300502 0.0314658 -0.121373 0.0300502 0.0378087 -0.119549 0.0300502 0.0429938 -0.114736 0.0273172 0.0558256 -0.112272 0.0300502 0.0614294 -0.109307 0.0300502 0.0652829 -0.103686 0.0273172 0.0768328 -0.0990869 0.0300502 0.0796086 -0.0931407 0.0273172 0.0937971 -0.0832082 0.0300502 0.0921244 -0.0894648 0.0325813 0.0960648 -0.0852198 0.0325813 0.0973829 -0.0789815 0.0300502 0.0984139 -0.0729892 0.0273172 0.101418 -0.0687547 0.0273172 0.113676 -0.0529071 0.0300502 0.114245 -0.0586432 0.0325813 0.116425 -0.0541862 0.0325813 0.111084 -0.0517008 0.0273172 0.112955 -0.047476 0.0273172 0.120141 -0.0358846 0.0300502 0.121685 -0.0410323 0.0325813 0.123045 -0.0367521 0.0325813 0.117401 -0.0350664 0.0273172 0.118528 -0.0310449 0.0273172 0.119494 -0.0270918 0.0273172 0.120308 -0.0232121 0.0273172 0.120979 -0.0194099 0.0273172 0.121518 -0.0156886 0.0273172 0.121932 -0.0120508 0.0273172 0.122231 -0.00849853 0.0273172 0.122423 -0.00503321 0.0273172 0.122515 -0.00165569 0.0273172 0.122515 0.00165569 0.0273172 0.122423 0.00503321 0.0273172 0.122231 0.00849853 0.0273172 0.121932 0.0120508 0.0273172 0.121518 0.0156886 0.0273172 0.120308 0.0232121 0.0273172 0.119494 0.0270918 0.0273172 0.121294 0.0317693 0.0300502 0.120141 0.0358846 0.0300502 0.116103 0.0391502 0.0273172 0.117299 0.0442995 0.0300502 0.11559 0.0485838 0.0300502 0.113676 0.0529071 0.0300502 0.111548 0.0572589 0.0300502 0.109195 0.0616271 0.0300502 0.10661 0.0659987 0.0300502 0.103784 0.070359 0.0300502 0.10071 0.0746923 0.0300502 0.0951624 0.0771806 0.0273172 0.0899498 0.0873529 0.0300502 0.0838821 0.0893114 0.0273172 0.0768328 0.0990869 0.0300502 0.0719438 0.102692 0.0300502 0.0684213 0.108671 0.0325813 0.0629146 0.111949 0.0325813 0.0600287 0.106814 0.0273172 0.0500091 0.114981 0.0300502 0.043997 0.117413 0.0300502 0.0378087 0.119549 0.0300502 0.0314658 0.121373 0.0300502 0.0249921 0.122869 0.0300502 0.0184129 0.124026 0.0300502 0.0120394 0.127851 0.0325813 0.00516905 0.128313 0.0325813 0.00493195 0.122427 0.0273172 -0.0150922 0.124474 0.0300502 -0.021714 0.123491 0.0300502 -0.0282438 0.122163 0.0300502 -0.0346551 0.120501 0.0300502 -0.0470263 0.116233 0.0300502 -0.0419129 0.121384 0.0325813 -0.0481633 0.119043 0.0325813 -0.0529429 0.11366 0.0300502 -0.067823 0.102043 0.0273172 -0.072723 0.0986108 0.0273172 -0.0773763 0.0950033 0.0273172 -0.0898107 0.0833473 0.0273172 -0.0934422 0.0792545 0.0273172 -0.0968195 0.0750914 0.0273172 -0.0999463 0.0708763 0.0273172 -0.0836855 0.0933715 0.0300502 -0.0879275 0.0893882 0.0300502 -0.102828 0.0666266 0.0273172 -0.107883 0.0580864 0.0273172 -0.110071 0.0538242 0.0273172 -0.112045 0.0495842 0.0273172 -0.113814 0.0453774 0.0273172 -0.117986 0.0330474 0.0273172 -0.119031 0.0290595 0.0273172 -0.119499 0.0379666 0.0300502 -0.118079 0.042175 0.0300502 -0.119919 0.0251425 0.0273172 -0.121265 0.0175389 0.0273172 -0.123476 0.0217981 0.0300502 -0.124581 0.0141825 0.0300502 -0.124945 0.0105034 0.0300502 -0.12234 0.00675494 0.0273172 -0.122481 0.00333343 0.0273172 -0.127046 0 0.0314822 -0.125195 -0.00691255 0.0300502 -0.124945 -0.0105034 0.0300502 -0.124094 -0.0179482 0.0300502 -0.123476 -0.0217981 0.0300502 -0.123658 -0.0346362 0.0325813 -0.124753 -0.0304565 0.0325813 -0.127848 -0.0312121 0.0348514 -0.119285 -0.0475588 0.0325813 -0.117432 -0.051968 0.0325813 -0.122245 -0.0487387 0.0348514 -0.120345 -0.0532572 0.0348514 -0.107771 -0.0698296 0.0325813 -0.110542 -0.0653561 0.0325813 -0.113284 -0.0669775 0.0348514 -0.0956225 -0.0811038 0.0300502 -0.0810961 -0.0995705 0.0325813 -0.0762191 -0.103351 0.0325813 -0.0728469 -0.109602 0.0348514 -0.0673277 -0.113076 0.0348514 -0.064147 -0.107734 0.0300502 -0.0542229 -0.116408 0.0325813 -0.0481633 -0.119043 0.0325813 -0.0419129 -0.121384 0.0325813 -0.035493 -0.123414 0.0325813 -0.0289266 -0.125116 0.0325813 -0.0158405 -0.130646 0.0348514 -0.0227907 -0.129614 0.0348514 -0.0150922 -0.124474 0.0300502 0.00516905 -0.128313 0.0325813 0.0120394 -0.127851 0.0325813 0.0188581 -0.127025 0.0325813 0.0255963 -0.12584 0.0325813 0.0322266 -0.124307 0.0325813 0.0450607 -0.120251 0.0325813 0.0396834 -0.125477 0.0348514 0.0461785 -0.123235 0.0348514 0.0512181 -0.117761 0.0325813 0.0571752 -0.114986 0.0325813 0.0629146 -0.111949 0.0325813 0.0684213 -0.108671 0.0325813 0.0736831 -0.105174 0.0325813 0.0786903 -0.101482 0.0325813 0.0834358 -0.0976183 0.0325813 0.0879146 -0.0936049 0.0325813 0.0899498 -0.0873529 0.0300502 0.103145 -0.0764981 0.0325813 0.102212 -0.0828977 0.0348514 0.105704 -0.0783959 0.0348514 0.10071 -0.0746923 0.0300502 0.106293 -0.07206 0.0325813 0.109187 -0.0675943 0.0325813 0.109195 -0.0616271 0.0300502 0.111548 -0.0572589 0.0300502 0.11559 -0.0485838 0.0300502 0.117299 -0.0442995 0.0300502 0.118812 -0.0400637 0.0300502 0.121294 -0.0317693 0.0300502 0.122282 -0.027724 0.0300502 0.123115 -0.0237537 0.0300502 0.123802 -0.0198628 0.0300502 0.124353 -0.0160546 0.0300502 0.124777 -0.012332 0.0300502 0.125083 -0.00869683 0.0300502 0.12528 -0.00515065 0.0300502 0.125374 -0.00169432 0.0300502 0.125374 0.00169432 0.0300502 0.12528 0.00515065 0.0300502 0.125083 0.00869683 0.0300502 0.124777 0.012332 0.0300502 0.126091 0.024328 0.0325813 0.129941 0.0208477 0.0348514 0.129219 0.0249315 0.0348514 0.123115 0.0237537 0.0300502 0.122282 0.027724 0.0300502 0.121685 0.0410323 0.0325813 0.126098 0.0376639 0.0348514 0.124704 0.0420502 0.0348514 0.118812 0.0400637 0.0300502 0.120135 0.0453705 0.0325813 0.118385 0.0497584 0.0325813 0.111835 0.063117 0.0325813 0.117079 0.060098 0.0348514 0.11461 0.0646828 0.0348514 0.106293 0.07206 0.0325813 0.111896 0.0692712 0.0348514 0.10893 0.0738477 0.0348514 0.103145 0.0764981 0.0325813 0.0997372 0.080891 0.0325813 0.0960648 0.0852198 0.0325813 0.0921244 0.0894648 0.0325813 0.0879146 0.0936049 0.0325813 0.0834358 0.0976183 0.0325813 0.0786903 0.101482 0.0325813 0.0736831 0.105174 0.0325813 0.0668062 0.106106 0.0300502 0.0571752 0.114986 0.0325813 0.0512181 0.117761 0.0325813 0.0450607 0.120251 0.0325813 0.0387228 0.122439 0.0325813 0.0322266 0.124307 0.0325813 0.0255963 0.12584 0.0325813 0.0193259 0.130176 0.0348514 0.0123381 0.131023 0.0348514 0.0117552 0.124833 0.0300502 -0.00172364 0.128405 0.0325813 -0.00860888 0.128128 0.0325813 -0.015457 0.127483 0.0325813 -0.022239 0.126476 0.0325813 -0.0289266 0.125116 0.0325813 -0.035493 0.123414 0.0325813 -0.0409236 0.118519 0.0300502 -0.0542229 0.116408 0.0325813 -0.0744199 0.100912 0.0300502 -0.0791818 0.09722 0.0300502 -0.0919063 0.0852921 0.0300502 -0.0956225 0.0811038 0.0300502 -0.0900532 0.0915493 0.0325813 -0.0857087 0.0956289 0.0325813 -0.113284 0.0669775 0.0348514 -0.116144 0.0686683 0.0368012 -0.115874 0.0623891 0.0348514 -0.1104 0.0594417 0.0300502 -0.11264 0.0550802 0.0300502 -0.11466 0.0507412 0.0300502 -0.11647 0.0464362 0.0300502 -0.110542 0.0653561 0.0325813 -0.120739 0.0338186 0.0300502 -0.121808 0.0297375 0.0300502 -0.122388 0.0388845 0.0325813 -0.120934 0.0431947 0.0325813 -0.122717 0.0257292 0.0300502 -0.124094 0.0179482 0.0300502 -0.127593 0.0145254 0.0325813 -0.127965 0.0107573 0.0325813 -0.125195 0.00691255 0.0300502 -0.125339 0.00341122 0.0300502 -0.149162 -0.00405959 0.0402139 -0.149355 0 0.040206 -0.152398 0 0.0398302 -0.128221 -0.00707967 0.0325813 -0.141854 -0.00386068 0.0395028 -0.14325 0 0.0398001 -0.145476 -0.00395927 0.0401362 -0.126461 -0.0223251 0.0325813 -0.13287 -0.0234565 0.0368012 -0.128802 -0.0270049 0.0348514 -0.129599 -0.0228789 0.0348514 -0.128591 -0.0408551 0.0368012 -0.125424 -0.0398491 0.0348514 -0.129924 -0.0363915 0.0368012 -0.123934 -0.0442662 0.0348514 -0.127063 -0.0453837 0.0368012 -0.115363 -0.0564118 0.0325813 -0.121209 -0.0592707 0.0368012 -0.115874 -0.0623891 0.0348514 -0.118225 -0.0578113 0.0348514 -0.110445 -0.0715619 0.0348514 -0.113233 -0.0733684 0.0368012 -0.10735 -0.0761264 0.0348514 -0.101474 -0.0787013 0.0325813 -0.103991 -0.0806538 0.0348514 -0.100364 -0.0851253 0.0348514 -0.105521 -0.0894997 0.0383714 -0.083108 -0.102041 0.0348514 -0.0781099 -0.105915 0.0348514 -0.0710835 -0.106949 0.0325813 -0.0615634 -0.116315 0.0348514 -0.055568 -0.119296 0.0348514 -0.0493581 -0.121996 0.0348514 -0.0429527 -0.124396 0.0348514 -0.0363735 -0.126476 0.0348514 -0.023366 -0.132886 0.0368012 -0.0303926 -0.131457 0.0368012 -0.022239 -0.126476 0.0325813 -0.00882245 -0.131306 0.0348514 -0.0017664 -0.131591 0.0348514 0.00529728 -0.131496 0.0348514 0.0123381 -0.131023 0.0348514 0.0193259 -0.130176 0.0348514 0.0262313 -0.128962 0.0348514 0.0406852 -0.128644 0.0368012 0.0338598 -0.130607 0.0368012 0.0387228 -0.122439 0.0325813 0.0524887 -0.120682 0.0348514 0.0585936 -0.117839 0.0348514 0.0718888 -0.114178 0.0368012 0.0701187 -0.111367 0.0348514 0.066103 -0.117623 0.0368012 0.0755111 -0.107784 0.0348514 0.0806425 -0.104 0.0348514 0.0855057 -0.10004 0.0348514 0.0900956 -0.0959271 0.0348514 0.0944099 -0.0916843 0.0348514 0.098448 -0.087334 0.0348514 0.0997372 -0.080891 0.0325813 0.10893 -0.0738477 0.0348514 0.111896 -0.0692712 0.0348514 0.111835 -0.063117 0.0325813 0.117079 -0.060098 0.0348514 0.119313 -0.0555305 0.0348514 0.118385 -0.0497584 0.0325813 0.120135 -0.0453705 0.0325813 0.127308 -0.0333446 0.0348514 0.129281 -0.0386147 0.0368012 0.130522 -0.0341863 0.0368012 0.124226 -0.0325374 0.0325813 0.125238 -0.0283942 0.0325813 0.126091 -0.024328 0.0325813 0.126795 -0.020343 0.0325813 0.12736 -0.0164428 0.0325813 0.127794 -0.0126301 0.0325813 0.128107 -0.00890709 0.0325813 0.128308 -0.00527517 0.0325813 0.128405 -0.00173528 0.0325813 0.128405 0.00173528 0.0325813 0.128308 0.00527517 0.0325813 0.128107 0.00890709 0.0325813 0.127794 0.0126301 0.0325813 0.12736 0.0164428 0.0325813 0.126795 0.020343 0.0325813 0.125238 0.0283942 0.0325813 0.124226 0.0325374 0.0325813 0.123045 0.0367521 0.0325813 0.119313 0.0555305 0.0348514 0.124384 0.0522801 0.0368012 0.122325 0.0569323 0.0368012 0.116425 0.0541862 0.0325813 0.114245 0.0586432 0.0325813 0.109187 0.0675943 0.0325813 0.104792 0.0849904 0.0368012 0.102212 0.0828977 0.0348514 0.108372 0.0803749 0.0368012 0.098448 0.087334 0.0348514 0.09237 0.0983487 0.0368012 0.0900956 0.0959271 0.0348514 0.0967932 0.0939988 0.0368012 0.0855057 0.10004 0.0348514 0.0806425 0.104 0.0348514 0.0718888 0.114178 0.0368012 0.0701187 0.111367 0.0348514 0.0774173 0.110505 0.0368012 0.0644754 0.114726 0.0348514 0.0585936 0.117839 0.0348514 0.0524887 0.120682 0.0348514 0.0461785 0.123235 0.0348514 0.0396834 0.125477 0.0348514 0.0268935 0.132217 0.0368012 0.0262313 0.128962 0.0348514 0.0338598 0.130607 0.0368012 0.0198138 0.133462 0.0368012 0.0188581 0.127025 0.0325813 0.00529728 0.131496 0.0348514 -0.0017664 0.131591 0.0348514 -0.00882245 0.131306 0.0348514 -0.0158405 0.130646 0.0348514 -0.0227907 0.129614 0.0348514 -0.0296442 0.12822 0.0348514 -0.044037 0.127536 0.0368012 -0.0429527 0.124396 0.0348514 -0.0372917 0.129669 0.0368012 -0.0493581 0.121996 0.0348514 -0.055568 0.119296 0.0348514 -0.0615634 0.116315 0.0348514 -0.0863762 0.117124 0.0401362 -0.0919032 0.11284 0.0401362 -0.0762191 0.103351 0.0325813 -0.0810961 0.0995705 0.0325813 -0.0941282 0.0873541 0.0325813 -0.0979343 0.0830646 0.0325813 -0.094617 0.0961889 0.0368012 -0.0922873 0.0938205 0.0348514 -0.0900523 0.100475 0.0368012 -0.104751 0.0742836 0.0325813 -0.087835 0.0980012 0.0348514 -0.107771 0.0698296 0.0325813 -0.113069 0.0608788 0.0325813 -0.115363 0.0564118 0.0325813 -0.117432 0.051968 0.0325813 -0.119285 0.0475588 0.0325813 -0.123658 0.0346362 0.0325813 -0.124753 0.0304565 0.0325813 -0.125424 0.0398491 0.0348514 -0.123934 0.0442662 0.0348514 -0.126461 0.0223251 0.0325813 -0.127094 0.0183821 0.0325813 -0.129599 0.0228789 0.0348514 -0.125684 0.0263512 0.0325813 -0.130758 0.0148857 0.0348514 -0.13114 0.0110242 0.0348514 -0.128369 0.00349369 0.0325813 -0.128221 0.00707967 0.0325813 -0.131402 -0.00725531 0.0348514 -0.13114 -0.0110242 0.0348514 -0.145018 -0.0121908 0.0401362 -0.144596 -0.016461 0.0401362 -0.140996 -0.0160512 0.0395028 -0.131075 -0.032 0.0368012 -0.132054 -0.0276866 0.0368012 -0.135421 -0.0283927 0.0383714 -0.126725 -0.0354954 0.0348514 -0.125331 -0.049969 0.0368012 -0.130303 -0.046541 0.0383714 -0.128527 -0.0512433 0.0383714 -0.116144 -0.0686683 0.0368012 -0.118799 -0.0639641 0.0368012 -0.121829 -0.0655952 0.0383714 -0.11006 -0.0780482 0.0368012 -0.112866 -0.0800384 0.0383714 -0.106617 -0.0826898 0.0368012 -0.0900523 -0.100475 0.0368012 -0.085206 -0.104617 0.0368012 -0.0765904 -0.115234 0.0383714 -0.0746859 -0.112369 0.0368012 -0.0821238 -0.111358 0.0383714 -0.0690273 -0.115931 0.0368012 -0.0631175 -0.119251 0.0368012 -0.0569708 -0.122307 0.0368012 -0.0506041 -0.125076 0.0368012 -0.044037 -0.127536 0.0368012 -0.0311676 -0.134809 0.0383714 -0.0382427 -0.132975 0.0383714 -0.0296442 -0.12822 0.0348514 -0.0162404 -0.133944 0.0368012 -0.00904517 -0.134621 0.0368012 -0.00181099 -0.134913 0.0368012 0.00543101 -0.134815 0.0368012 0.0126496 -0.13433 0.0368012 0.0198138 -0.133462 0.0368012 0.0268935 -0.132217 0.0368012 0.033026 -0.127391 0.0348514 0.0473443 -0.126346 0.0368012 0.0538138 -0.123729 0.0368012 0.0600728 -0.120814 0.0368012 0.0644754 -0.114726 0.0348514 0.0774173 -0.110505 0.0368012 0.0898996 -0.105181 0.0383714 0.0876642 -0.102565 0.0368012 0.0847866 -0.109344 0.0383714 0.09237 -0.0983487 0.0368012 0.0967932 -0.0939988 0.0368012 0.100933 -0.0895387 0.0368012 0.104792 -0.0849904 0.0368012 0.108372 -0.0803749 0.0368012 0.11168 -0.0757119 0.0368012 0.114721 -0.0710199 0.0368012 0.11461 -0.0646828 0.0348514 0.120034 -0.0616151 0.0368012 0.122325 -0.0569323 0.0368012 0.121322 -0.0509928 0.0348514 0.123115 -0.0464961 0.0348514 0.124704 -0.0420502 0.0348514 0.126098 -0.0376639 0.0348514 0.128345 -0.0290986 0.0348514 0.129219 -0.0249315 0.0348514 0.129941 -0.0208477 0.0348514 0.130519 -0.0168507 0.0348514 0.130964 -0.0129434 0.0348514 0.131286 -0.00912806 0.0348514 0.131491 -0.00540604 0.0348514 0.131591 -0.00177833 0.0348514 0.131591 0.00177833 0.0348514 0.131491 0.00540604 0.0348514 0.131286 0.00912806 0.0348514 0.130964 0.0129434 0.0348514 0.130519 0.0168507 0.0348514 0.133221 0.0213739 0.0368012 0.132481 0.0255609 0.0368012 0.128345 0.0290986 0.0348514 0.127308 0.0333446 0.0348514 0.129281 0.0386147 0.0368012 0.127852 0.0431118 0.0368012 0.123115 0.0464961 0.0348514 0.121322 0.0509928 0.0348514 0.120034 0.0616151 0.0368012 0.117503 0.0663157 0.0368012 0.114721 0.0710199 0.0368012 0.11168 0.0757119 0.0368012 0.105704 0.0783959 0.0348514 0.100933 0.0895387 0.0368012 0.0944099 0.0916843 0.0348514 0.0876642 0.102565 0.0368012 0.0826783 0.106625 0.0368012 0.0755111 0.107784 0.0348514 0.066103 0.117623 0.0368012 0.0600728 0.120814 0.0368012 0.0538138 0.123729 0.0368012 0.0473443 0.126346 0.0368012 0.0347232 0.133938 0.0383714 0.0417227 0.131925 0.0383714 0.033026 0.127391 0.0348514 0.0126496 0.13433 0.0368012 0.00543101 0.134815 0.0368012 -0.00181099 0.134913 0.0368012 -0.00904517 0.134621 0.0368012 -0.0162404 0.133944 0.0368012 -0.023366 0.132886 0.0368012 -0.0382427 0.132975 0.0383714 -0.0311676 0.134809 0.0383714 -0.0363735 0.126476 0.0348514 -0.0506041 0.125076 0.0368012 -0.0569708 0.122307 0.0368012 -0.0707875 0.118887 0.0383714 -0.064727 0.122292 0.0383714 -0.083108 0.102041 0.0348514 -0.0964634 0.0895212 0.0348514 -0.10735 0.0761264 0.0348514 -0.130303 0.046541 0.0383714 -0.133638 0.0477321 0.0395028 -0.13187 0.0418969 0.0383714 -0.110445 0.0715619 0.0348514 -0.118225 0.0578113 0.0348514 -0.120345 0.0532572 0.0348514 -0.122245 0.0487387 0.0348514 -0.126725 0.0354954 0.0348514 -0.127848 0.0312121 0.0348514 -0.127063 0.0453837 0.0368012 -0.128591 0.0408551 0.0368012 -0.128802 0.0270049 0.0348514 -0.130247 0.0188381 0.0348514 -0.13287 0.0234565 0.0368012 -0.134059 0.0152615 0.0368012 -0.13445 0.0113025 0.0368012 -0.131554 0.00358036 0.0348514 -0.131402 0.00725531 0.0348514 -0.137404 0 0.0379785 -0.138314 -0.00376435 0.0383714 -0.13472 -0.00743846 0.0368012 -0.13445 -0.0113025 0.0368012 -0.134059 -0.0152615 0.0368012 -0.133535 -0.0193137 0.0368012 -0.144031 -0.0208317 0.0401362 -0.140445 -0.0203131 0.0395028 -0.133237 -0.0373195 0.0383714 -0.134418 -0.032816 0.0383714 -0.137858 -0.0336558 0.0395028 -0.135245 -0.0429691 0.0395028 -0.13187 -0.0418969 0.0383714 -0.136647 -0.0382746 0.0395028 -0.123383 -0.0546016 0.0368012 -0.126529 -0.055994 0.0383714 -0.116121 -0.0752393 0.0383714 -0.119105 -0.0704193 0.0383714 -0.122154 -0.0722215 0.0395028 -0.112133 -0.0869686 0.0395028 -0.0923487 -0.103037 0.0383714 -0.0873787 -0.107284 0.0383714 -0.0800817 -0.108589 0.0368012 -0.0707875 -0.118887 0.0383714 -0.064727 -0.122292 0.0383714 -0.0584236 -0.125426 0.0383714 -0.0518945 -0.128265 0.0383714 -0.0392214 -0.136379 0.0395028 -0.0463157 -0.134135 0.0395028 -0.0372917 -0.129669 0.0368012 -0.0239619 -0.136275 0.0383714 -0.0166545 -0.137359 0.0383714 -0.00927582 -0.138054 0.0383714 -0.00185717 -0.138353 0.0383714 0.0055695 -0.138253 0.0383714 0.0129721 -0.137756 0.0383714 0.020319 -0.136865 0.0383714 0.0356118 -0.137365 0.0395028 0.0347232 -0.133938 0.0383714 0.0282851 -0.139059 0.0395028 0.0417227 -0.131925 0.0383714 0.0485516 -0.129567 0.0383714 0.055186 -0.126884 0.0383714 0.0695235 -0.123709 0.0395028 0.0677886 -0.120622 0.0383714 0.0631812 -0.127065 0.0395028 0.073722 -0.11709 0.0383714 0.0793914 -0.113322 0.0383714 0.0826783 -0.106625 0.0368012 0.0947255 -0.100857 0.0383714 0.0992614 -0.0963958 0.0383714 0.103507 -0.0918219 0.0383714 0.107464 -0.0871577 0.0383714 0.111136 -0.0824245 0.0383714 0.123583 -0.0697472 0.0395028 0.120499 -0.0680068 0.0383714 0.120657 -0.0746948 0.0395028 0.117503 -0.0663157 0.0368012 0.127556 -0.0536132 0.0383714 0.128655 -0.0598783 0.0395028 0.130821 -0.0549853 0.0395028 0.124384 -0.0522801 0.0368012 0.126223 -0.0476698 0.0368012 0.127852 -0.0431118 0.0368012 0.132578 -0.0395994 0.0383714 0.13385 -0.0350581 0.0383714 0.131585 -0.0298332 0.0368012 0.132481 -0.0255609 0.0368012 0.133221 -0.0213739 0.0368012 0.133814 -0.0172761 0.0368012 0.134271 -0.0132702 0.0368012 0.1346 -0.00935849 0.0368012 0.134811 -0.00554251 0.0368012 0.134912 -0.00182322 0.0368012 0.134912 0.00182322 0.0368012 0.134811 0.00554251 0.0368012 0.1346 0.00935849 0.0368012 0.134271 0.0132702 0.0368012 0.133814 0.0172761 0.0368012 0.134941 0.030594 0.0383714 0.139337 0.0268835 0.0395028 0.138394 0.0313769 0.0395028 0.131585 0.0298332 0.0368012 0.130522 0.0341863 0.0368012 0.132578 0.0395994 0.0383714 0.131112 0.0442111 0.0383714 0.126223 0.0476698 0.0368012 0.127556 0.0536132 0.0383714 0.125444 0.0583841 0.0383714 0.123095 0.0631863 0.0383714 0.120499 0.0680068 0.0383714 0.117646 0.0728309 0.0383714 0.114528 0.0776426 0.0383714 0.107464 0.0871577 0.0383714 0.111136 0.0824245 0.0383714 0.103507 0.0918219 0.0383714 0.0947255 0.100857 0.0383714 0.0992614 0.0963958 0.0383714 0.0898996 0.105181 0.0383714 0.0814232 0.116223 0.0395028 0.0793914 0.113322 0.0383714 0.0869564 0.112143 0.0395028 0.073722 0.11709 0.0383714 0.0677886 0.120622 0.0383714 0.0616047 0.123894 0.0383714 0.055186 0.126884 0.0383714 0.0427904 0.135301 0.0395028 0.0497941 0.132883 0.0395028 0.0406852 0.128644 0.0368012 0.0275793 0.135589 0.0383714 0.020319 0.136865 0.0383714 0.0129721 0.137756 0.0383714 0.0055695 0.138253 0.0383714 -0.00185717 0.138353 0.0383714 -0.00927582 0.138054 0.0383714 -0.0166545 0.137359 0.0383714 -0.0319652 0.138259 0.0395028 -0.0245751 0.139762 0.0395028 -0.0303926 0.131457 0.0368012 -0.04516 0.130788 0.0383714 -0.0518945 0.128265 0.0383714 -0.0584236 0.125426 0.0383714 -0.0631175 0.119251 0.0368012 -0.085206 0.104617 0.0368012 -0.0988985 0.0917811 0.0368012 -0.128447 0.0759424 0.0402139 -0.106617 0.0826898 0.0368012 -0.11006 0.0780482 0.0368012 -0.0970298 0.0986418 0.0383714 -0.0923487 0.103037 0.0383714 -0.113233 0.0733684 0.0368012 -0.118799 0.0639641 0.0368012 -0.121209 0.0592707 0.0368012 -0.123383 0.0546016 0.0368012 -0.125331 0.049969 0.0368012 -0.119105 0.0704193 0.0383714 -0.129924 0.0363915 0.0368012 -0.131075 0.032 0.0368012 -0.132054 0.0276866 0.0368012 -0.133535 0.0193137 0.0368012 -0.136258 0.0240546 0.0383714 -0.137477 0.0156507 0.0383714 -0.137879 0.0115907 0.0383714 -0.134875 0.00367074 0.0368012 -0.13472 0.00743846 0.0368012 -0.140279 0 0.0390434 -0.138155 -0.00762815 0.0383714 -0.137879 -0.0115907 0.0383714 -0.137477 -0.0156507 0.0383714 -0.13694 -0.0198062 0.0383714 -0.136258 -0.0240546 0.0383714 -0.143314 -0.0253002 0.0401362 -0.138887 -0.0291193 0.0395028 -0.139746 -0.0246702 0.0395028 -0.13705 -0.0489509 0.0401362 -0.133638 -0.0477321 0.0395028 -0.138698 -0.0440663 0.0401362 -0.131816 -0.0525547 0.0395028 -0.135182 -0.0538966 0.0401362 -0.1243 -0.0607821 0.0383714 -0.127481 -0.0623376 0.0395028 -0.119092 -0.0771649 0.0395028 -0.109335 -0.0847984 0.0383714 -0.099513 -0.101166 0.0395028 -0.0947121 -0.105674 0.0395028 -0.0863762 -0.117124 0.0401362 -0.0842256 -0.114208 0.0395028 -0.0919032 -0.11284 0.0401362 -0.0785505 -0.118183 0.0395028 -0.0725991 -0.121929 0.0395028 -0.0663835 -0.125422 0.0395028 -0.0599187 -0.128636 0.0395028 -0.0474984 -0.13756 0.0401362 -0.0545816 -0.134907 0.0401362 -0.04516 -0.130788 0.0383714 -0.0319652 -0.138259 0.0395028 -0.0245751 -0.139762 0.0395028 -0.0170807 -0.140875 0.0395028 -0.00951321 -0.141587 0.0395028 -0.0019047 -0.141894 0.0395028 0.00571204 -0.141791 0.0395028 0.0133041 -0.141281 0.0395028 0.0290073 -0.14261 0.0401362 0.0213712 -0.143952 0.0401362 0.0275793 -0.135589 0.0383714 0.0427904 -0.135301 0.0395028 0.0497941 -0.132883 0.0395028 0.0565984 -0.130131 0.0395028 0.0616047 -0.123894 0.0383714 0.0756087 -0.120086 0.0395028 0.0814232 -0.116223 0.0395028 0.0922003 -0.107873 0.0395028 0.0869564 -0.112143 0.0395028 0.104401 -0.101387 0.0401362 0.101802 -0.0988627 0.0395028 0.0996304 -0.106079 0.0401362 0.106156 -0.0941718 0.0395028 0.110214 -0.0893882 0.0395028 0.11398 -0.0845339 0.0395028 0.114528 -0.0776426 0.0383714 0.117646 -0.0728309 0.0383714 0.123095 -0.0631863 0.0383714 0.125444 -0.0583841 0.0383714 0.129442 -0.0488854 0.0383714 0.131112 -0.0442111 0.0383714 0.142895 -0.02757 0.0401362 0.145524 -0.0329935 0.0402139 0.146515 -0.0282686 0.0402139 0.134941 -0.030594 0.0383714 0.13586 -0.0262127 0.0383714 0.136618 -0.021919 0.0383714 0.137226 -0.0177166 0.0383714 0.137695 -0.0136086 0.0383714 0.138032 -0.00959713 0.0383714 0.138249 -0.00568385 0.0383714 0.138353 -0.00186972 0.0383714 0.138353 0.00186972 0.0383714 0.138249 0.00568385 0.0383714 0.138032 0.00959713 0.0383714 0.137695 0.0136086 0.0383714 0.137226 0.0177166 0.0383714 0.136618 0.021919 0.0383714 0.13586 0.0262127 0.0383714 0.13385 0.0350581 0.0383714 0.136144 0.0514167 0.0401362 0.132755 0.0501365 0.0395028 0.137901 0.0465004 0.0401362 0.129442 0.0488854 0.0383714 0.130821 0.0549853 0.0395028 0.128655 0.0598783 0.0395028 0.126246 0.0648034 0.0395028 0.123583 0.0697472 0.0395028 0.120657 0.0746948 0.0395028 0.117459 0.0796296 0.0395028 0.110214 0.0893882 0.0395028 0.11398 0.0845339 0.0395028 0.104401 0.101387 0.0401362 0.101802 0.0988627 0.0395028 0.108867 0.0965765 0.0401362 0.0971497 0.103438 0.0395028 0.0922003 0.107873 0.0395028 0.0847866 0.109344 0.0383714 0.0756087 0.120086 0.0395028 0.0695235 0.123709 0.0395028 0.0631812 0.127065 0.0395028 0.0510656 0.136276 0.0401362 0.0580436 0.133454 0.0401362 0.0485516 0.129567 0.0383714 0.0356118 0.137365 0.0395028 0.0282851 0.139059 0.0395028 0.020839 0.140368 0.0395028 0.0133041 0.141281 0.0395028 0.00571204 0.141791 0.0395028 -0.0019047 0.141894 0.0395028 -0.00951321 0.141587 0.0395028 -0.0252026 0.143331 0.0401362 -0.0175169 0.144472 0.0401362 -0.0239619 0.136275 0.0383714 -0.0392214 0.136379 0.0395028 -0.0463157 0.134135 0.0395028 -0.0532226 0.131548 0.0395028 -0.0599187 0.128636 0.0395028 -0.0725991 0.121929 0.0395028 -0.0663835 0.125422 0.0395028 -0.0785505 0.118183 0.0395028 -0.10142 0.0941215 0.0383714 -0.105521 0.0894997 0.0383714 -0.109335 0.0847984 0.0383714 -0.112866 0.0800384 0.0383714 -0.099513 0.101166 0.0395028 -0.0947121 0.105674 0.0395028 -0.116121 0.0752393 0.0383714 -0.121829 0.0655952 0.0383714 -0.1243 0.0607821 0.0383714 -0.126529 0.055994 0.0383714 -0.128527 0.0512433 0.0383714 -0.122154 0.0722215 0.0395028 -0.133237 0.0373195 0.0383714 -0.134418 0.032816 0.0383714 -0.135245 0.0429691 0.0395028 -0.135421 0.0283927 0.0383714 -0.13694 0.0198062 0.0383714 -0.140996 0.0160512 0.0395028 -0.141408 0.0118873 0.0395028 -0.138155 0.00762815 0.0383714 -0.138314 0.00376435 0.0383714 -0.16374 0 0.0353308 -0.163825 -0.00445866 0.0352405 -0.161064 0 0.0368279 -0.141691 -0.00782337 0.0395028 -0.141408 -0.0118873 0.0395028 -0.141378 -0.0345152 0.0401362 -0.142433 -0.0298628 0.0401362 -0.146042 -0.0306195 0.0402139 -0.140137 -0.0392519 0.0401362 -0.14496 -0.0353898 0.0402139 -0.129767 -0.057427 0.0395028 -0.133081 -0.0588934 0.0401362 -0.138607 -0.0552623 0.0402139 -0.136453 -0.0603856 0.0402139 -0.124947 -0.0672739 0.0395028 -0.128137 -0.0689917 0.0401362 -0.125273 -0.0740657 0.0401362 -0.128447 -0.0759424 0.0402139 -0.122133 -0.0791353 0.0401362 -0.115755 -0.0820868 0.0395028 -0.118711 -0.0841828 0.0401362 -0.102054 -0.103749 0.0401362 -0.0971305 -0.108373 0.0401362 -0.0896149 -0.11003 0.0395028 -0.0805563 -0.121201 0.0401362 -0.0744529 -0.125043 0.0401362 -0.0680786 -0.128624 0.0401362 -0.0559647 -0.138325 0.0402139 -0.0630058 -0.135263 0.0402139 -0.0532226 -0.131548 0.0395028 -0.0402229 -0.139861 0.0401362 -0.0327814 -0.14179 0.0401362 -0.0252026 -0.143331 0.0401362 -0.0175169 -0.144472 0.0401362 -0.00975612 -0.145203 0.0401362 -0.00195333 -0.145517 0.0401362 0.00585789 -0.145412 0.0401362 0.0219127 -0.1476 0.0402139 0.0139896 -0.14856 0.0402139 0.020839 -0.140368 0.0395028 0.0365212 -0.140873 0.0401362 0.0438831 -0.138756 0.0401362 0.0510656 -0.136276 0.0401362 0.0580436 -0.133454 0.0401362 0.0712987 -0.126868 0.0401362 0.0647945 -0.13031 0.0401362 0.0775393 -0.123153 0.0401362 0.0914365 -0.11792 0.0402139 0.0891768 -0.115006 0.0401362 0.0856182 -0.12221 0.0402139 0.0945546 -0.110627 0.0401362 0.0971497 -0.103438 0.0395028 0.115893 -0.0939936 0.0402139 0.113028 -0.0916707 0.0401362 0.111625 -0.0990236 0.0402139 0.12351 -0.0837322 0.0402139 0.120458 -0.0816629 0.0401362 0.119852 -0.0888891 0.0402139 0.117459 -0.0796296 0.0395028 0.126739 -0.0715282 0.0401362 0.123738 -0.0766021 0.0401362 0.126246 -0.0648034 0.0395028 0.13194 -0.0614072 0.0401362 0.134161 -0.0563893 0.0401362 0.132755 -0.0501365 0.0395028 0.134467 -0.0453426 0.0395028 0.135971 -0.0406128 0.0395028 0.137276 -0.0359553 0.0395028 0.138394 -0.0313769 0.0395028 0.139337 -0.0268835 0.0395028 0.140115 -0.0224799 0.0395028 0.140738 -0.01817 0.0395028 0.141218 -0.0139569 0.0395028 0.141565 -0.00984275 0.0395028 0.141787 -0.00582931 0.0395028 0.141893 -0.00191757 0.0395028 0.141893 0.00191757 0.0395028 0.141787 0.00582931 0.0395028 0.141565 0.00984275 0.0395028 0.141218 0.0139569 0.0395028 0.140738 0.01817 0.0395028 0.140115 0.0224799 0.0395028 0.142895 0.02757 0.0401362 0.141928 0.0321781 0.0401362 0.137276 0.0359553 0.0395028 0.135971 0.0406128 0.0395028 0.134467 0.0453426 0.0395028 0.134161 0.0563893 0.0401362 0.13194 0.0614072 0.0401362 0.126873 0.0785431 0.0402139 0.123738 0.0766021 0.0401362 0.12995 0.0733406 0.0402139 0.120458 0.0816629 0.0401362 0.113028 0.0916707 0.0401362 0.11689 0.0866925 0.0401362 0.106156 0.0941718 0.0395028 0.0996304 0.106079 0.0401362 0.0914365 0.11792 0.0402139 0.0891768 0.115006 0.0401362 0.0969506 0.11343 0.0402139 0.0835023 0.11919 0.0401362 0.0775393 0.123153 0.0401362 0.0712987 0.126868 0.0401362 0.0595143 0.136835 0.0402139 0.0664364 0.133612 0.0402139 0.0565984 0.130131 0.0395028 0.0438831 0.138756 0.0401362 0.0365212 0.140873 0.0401362 0.0290073 0.14261 0.0401362 0.0213712 0.143952 0.0401362 0.0136438 0.144889 0.0401362 0.00585789 0.145412 0.0401362 -0.00195333 0.145517 0.0401362 -0.0179607 0.148133 0.0402139 -0.0100033 0.148882 0.0402139 -0.0170807 0.140875 0.0395028 -0.0327814 0.14179 0.0401362 -0.0402229 0.139861 0.0401362 -0.0474984 0.13756 0.0401362 -0.0698037 0.131884 0.0402139 -0.0680786 0.128624 0.0401362 -0.0744529 0.125043 0.0401362 -0.0805563 0.121201 0.0401362 -0.104016 0.0965303 0.0395028 -0.108222 0.0917902 0.0395028 -0.112133 0.0869686 0.0395028 -0.115755 0.0820868 0.0395028 -0.102054 0.103749 0.0401362 -0.0971305 0.108373 0.0401362 -0.119092 0.0771649 0.0395028 -0.124947 0.0672739 0.0395028 -0.127481 0.0623376 0.0395028 -0.129767 0.057427 0.0395028 -0.131816 0.0525547 0.0395028 -0.125273 0.0740657 0.0401362 -0.142212 0.0451829 0.0402139 -0.138698 0.0440663 0.0401362 -0.140523 0.0501913 0.0402139 -0.136647 0.0382746 0.0395028 -0.137858 0.0336558 0.0395028 -0.13705 0.0489509 0.0401362 -0.139746 0.0246702 0.0395028 -0.138887 0.0291193 0.0395028 -0.140445 0.0203131 0.0395028 -0.143314 0.0253002 0.0401362 -0.144596 0.016461 0.0401362 -0.145018 0.0121908 0.0401362 -0.141854 0.00386068 0.0395028 -0.141691 0.00782337 0.0395028 -0.146289 0 0.0401985 -0.145309 -0.00802313 0.0401362 -0.160257 -0.00436155 0.0371966 -0.156595 -0.00426189 0.0387046 -0.158273 0 0.0381 -0.151958 -0.0172991 0.039724 -0.156103 -0.0131226 0.0387046 -0.155648 -0.0177192 0.0387046 -0.15504 -0.022424 0.0387046 -0.151364 -0.0218924 0.039724 -0.147271 -0.0412503 0.039724 -0.14576 -0.0463099 0.039724 -0.142212 -0.0451829 0.0402139 -0.144028 -0.0514432 0.039724 -0.140523 -0.0501913 0.0402139 -0.130736 -0.0639294 0.0401362 -0.131384 -0.0707399 0.0402139 -0.134049 -0.0655493 0.0402139 -0.137393 -0.0671843 0.039724 -0.125228 -0.0811405 0.0402139 -0.128352 -0.0831643 0.039724 -0.10464 -0.106378 0.0402139 -0.0995917 -0.111119 0.0402139 -0.102076 -0.11389 0.039724 -0.094232 -0.115699 0.0402139 -0.0885649 -0.120092 0.0402139 -0.0825975 -0.124272 0.0402139 -0.0763395 -0.128211 0.0402139 -0.0698037 -0.131884 0.0402139 -0.0715447 -0.135173 0.039724 -0.0614487 -0.13192 0.0401362 -0.0487019 -0.141046 0.0402139 -0.0412421 -0.143405 0.0402139 -0.0336121 -0.145383 0.0402139 -0.0258412 -0.146963 0.0402139 -0.0179607 -0.148133 0.0402139 -0.0100033 -0.148882 0.0402139 -0.00200283 -0.149204 0.0402139 -0.00205279 -0.152926 0.039724 0.00600632 -0.149097 0.0402139 0.00615614 -0.152815 0.039724 0.0136438 -0.144889 0.0401362 0.0297424 -0.146223 0.0402139 0.0374466 -0.144442 0.0402139 0.044995 -0.142272 0.0402139 0.0523595 -0.13973 0.0402139 0.0595143 -0.136835 0.0402139 0.0609988 -0.140248 0.039724 0.0664364 -0.133612 0.0402139 0.0731054 -0.130083 0.0402139 0.0795041 -0.126273 0.0402139 0.0835023 -0.11919 0.0401362 0.0969506 -0.11343 0.0402139 0.107047 -0.103956 0.0402139 0.102155 -0.108767 0.0402139 0.108867 -0.0965765 0.0401362 0.11689 -0.0866925 0.0401362 0.12995 -0.0733406 0.0402139 0.126873 -0.0785431 0.0402139 0.129469 -0.0664581 0.0401362 0.135283 -0.0629632 0.0402139 0.137561 -0.0578182 0.0402139 0.136144 -0.0514167 0.0401362 0.137901 -0.0465004 0.0401362 0.139443 -0.0416498 0.0401362 0.140781 -0.0368734 0.0401362 0.141928 -0.0321781 0.0401362 0.143692 -0.0230539 0.0401362 0.144332 -0.018634 0.0401362 0.144824 -0.0143132 0.0401362 0.145179 -0.0100941 0.0401362 0.145407 -0.00597816 0.0401362 0.145517 -0.00196653 0.0401362 0.145517 0.00196653 0.0401362 0.145407 0.00597816 0.0401362 0.145179 0.0100941 0.0401362 0.144824 0.0143132 0.0401362 0.144332 0.018634 0.0401362 0.143692 0.0230539 0.0401362 0.145524 0.0329935 0.0402139 0.149154 0.0338164 0.039724 0.144348 0.0378077 0.0402139 0.140781 0.0368734 0.0401362 0.139443 0.0416498 0.0401362 0.139594 0.0527196 0.0402139 0.141395 0.0476786 0.0402139 0.135283 0.0629632 0.0402139 0.138657 0.0645337 0.039724 0.13275 0.0681421 0.0402139 0.129469 0.0664581 0.0401362 0.126739 0.0715282 0.0401362 0.12351 0.0837322 0.0402139 0.126591 0.0858207 0.039724 0.119852 0.0888891 0.0402139 0.115893 0.0939936 0.0402139 0.107047 0.103956 0.0402139 0.111625 0.0990236 0.0402139 0.102155 0.108767 0.0402139 0.0945546 0.110627 0.0401362 0.0856182 0.12221 0.0402139 0.0795041 0.126273 0.0402139 0.0731054 0.130083 0.0402139 0.0647945 0.13031 0.0401362 0.0523595 0.13973 0.0402139 0.044995 0.142272 0.0402139 0.0374466 0.144442 0.0402139 0.0297424 0.146223 0.0402139 0.0219127 0.1476 0.0402139 0.0139896 0.14856 0.0402139 0.00600632 0.149097 0.0402139 -0.00200283 0.149204 0.0402139 -0.00205279 0.152926 0.039724 -0.00975612 0.145203 0.0401362 -0.0258412 0.146963 0.0402139 -0.0336121 0.145383 0.0402139 -0.0412421 0.143405 0.0402139 -0.0487019 0.141046 0.0402139 -0.0763395 0.128211 0.0402139 -0.0825975 0.124272 0.0402139 -0.0846577 0.127372 0.039724 -0.0885649 0.120092 0.0402139 -0.106672 0.0989952 0.0401362 -0.110985 0.094134 0.0401362 -0.114997 0.0891893 0.0401362 -0.118711 0.0841828 0.0401362 -0.122133 0.0791353 0.0401362 -0.128137 0.0689917 0.0401362 -0.130736 0.0639294 0.0401362 -0.133081 0.0588934 0.0401362 -0.135182 0.0538966 0.0401362 -0.140137 0.0392519 0.0401362 -0.141378 0.0345152 0.0401362 -0.142433 0.0298628 0.0401362 -0.144031 0.0208317 0.0401362 -0.146945 0.0259413 0.0402139 -0.14826 0.0168781 0.0402139 -0.148693 0.0124997 0.0402139 -0.145476 0.00395927 0.0401362 -0.145309 0.00802313 0.0401362 -0.152883 -0.00416085 0.039724 -0.148991 -0.00822643 0.0402139 -0.148693 -0.0124997 0.0402139 -0.14826 -0.0168781 0.0402139 -0.147681 -0.0213596 0.0402139 -0.146945 -0.0259413 0.0402139 -0.154268 -0.027234 0.0387046 -0.149685 -0.0313832 0.039724 -0.15061 -0.0265883 0.039724 -0.148576 -0.0362725 0.039724 -0.15332 -0.0321454 0.0387046 -0.143687 -0.0402465 0.0402139 -0.142064 -0.0566407 0.039724 -0.147526 -0.0526924 0.0387046 -0.145514 -0.0580162 0.0387046 -0.131651 -0.0778366 0.039724 -0.134661 -0.0725043 0.039724 -0.137931 -0.074265 0.0387046 -0.112103 -0.104035 0.039724 -0.0965824 -0.118585 0.039724 -0.090774 -0.123088 0.039724 -0.0782436 -0.131409 0.039724 -0.0801436 -0.1346 0.0387046 -0.0645773 -0.138637 0.039724 -0.0573606 -0.141775 0.039724 -0.0499167 -0.144564 0.039724 -0.0422708 -0.146982 0.039724 -0.0344505 -0.149009 0.039724 -0.0264858 -0.150629 0.039724 -0.0102528 -0.152595 0.039724 -0.0105018 -0.156301 0.0387046 0.0143385 -0.152266 0.039724 0.0224592 -0.151281 0.039724 0.0304842 -0.14987 0.039724 0.0383806 -0.148045 0.039724 0.0536655 -0.143215 0.039724 0.0549687 -0.146693 0.0387046 0.0680935 -0.136944 0.039724 0.0749288 -0.133327 0.039724 0.0877537 -0.125259 0.039724 0.0937172 -0.120862 0.039724 0.104703 -0.11148 0.039724 0.114409 -0.101494 0.039724 0.122842 -0.0911063 0.039724 0.136061 -0.0698417 0.039724 0.133191 -0.0751699 0.039724 0.136426 -0.0769953 0.0387046 0.13275 -0.0681421 0.0402139 0.140992 -0.0592603 0.039724 0.144416 -0.0606994 0.0387046 0.143076 -0.0540345 0.039724 0.139594 -0.0527196 0.0402139 0.141395 -0.0476786 0.0402139 0.142976 -0.0427052 0.0402139 0.144348 -0.0378077 0.0402139 0.147333 -0.0236381 0.0402139 0.15017 -0.0289737 0.039724 0.147989 -0.0191061 0.0402139 0.148494 -0.0146759 0.0402139 0.148858 -0.0103498 0.0402139 0.149092 -0.00612964 0.0402139 0.149204 -0.00201636 0.0402139 0.149204 0.00201636 0.0402139 0.149092 0.00612964 0.0402139 0.148858 0.0103498 0.0402139 0.148494 0.0146759 0.0402139 0.147989 0.0191061 0.0402139 0.147333 0.0236381 0.0402139 0.146515 0.0282686 0.0402139 0.142976 0.0427052 0.0402139 0.144922 0.0488679 0.039724 0.137561 0.0578182 0.0402139 0.133191 0.0751699 0.039724 0.114409 0.101494 0.039724 0.118783 0.096338 0.039724 0.121668 0.0986774 0.0387046 0.0993688 0.11626 0.039724 0.104703 0.11148 0.039724 0.107245 0.114187 0.0387046 0.0937172 0.120862 0.039724 0.0877537 0.125259 0.039724 0.0680935 0.136944 0.039724 0.0749288 0.133327 0.039724 0.0767484 0.136565 0.0387046 0.0609988 0.140248 0.039724 0.0536655 0.143215 0.039724 0.0461173 0.145821 0.039724 0.0383806 0.148045 0.039724 0.0304842 0.14987 0.039724 0.00615614 0.152815 0.039724 0.0143385 0.152266 0.039724 0.0146867 0.155963 0.0387046 0.00630563 0.156526 0.0387046 -0.0102528 0.152595 0.039724 -0.0184087 0.151827 0.039724 -0.0264858 0.150629 0.039724 -0.0344505 0.149009 0.039724 -0.0422708 0.146982 0.039724 -0.0715447 0.135173 0.039724 -0.090774 0.123088 0.039724 -0.109375 0.101504 0.0402139 -0.113798 0.0965193 0.0402139 -0.117911 0.0914492 0.0402139 -0.121719 0.0863159 0.0402139 -0.125228 0.0811405 0.0402139 -0.134049 0.0655493 0.0402139 -0.136453 0.0603856 0.0402139 -0.138607 0.0552623 0.0402139 -0.14496 0.0353898 0.0402139 -0.143687 0.0402465 0.0402139 -0.147271 0.0412503 0.039724 -0.14576 0.0463099 0.039724 -0.144028 0.0514432 0.039724 -0.146042 0.0306195 0.0402139 -0.147681 0.0213596 0.0402139 -0.15061 0.0265883 0.039724 -0.148991 0.00822643 0.0402139 -0.149162 0.00405959 0.0402139 -0.155379 0 0.0391128 -0.152707 -0.00843162 0.039724 -0.152402 -0.0128115 0.039724 -0.152184 -0.0371533 0.0387046 -0.15279 -0.0485437 0.0371966 -0.149299 -0.0474345 0.0387046 -0.154375 -0.0432401 0.0371966 -0.139857 -0.0618918 0.039724 -0.143253 -0.0633948 0.0387046 -0.148917 -0.0593728 0.0371966 -0.146603 -0.0648772 0.0371966 -0.131469 -0.0851839 0.0387046 -0.134848 -0.0797268 0.0387046 -0.138001 -0.0815911 0.0371966 -0.119468 -0.101329 0.0387046 -0.114825 -0.106562 0.0387046 -0.10725 -0.109032 0.039724 -0.104555 -0.116656 0.0387046 -0.0989277 -0.121464 0.0387046 -0.0929783 -0.126077 0.0387046 -0.0846577 -0.127372 0.039724 -0.0732821 -0.138456 0.0387046 -0.0661455 -0.142004 0.0387046 -0.0587535 -0.145218 0.0387046 -0.0511289 -0.148075 0.0387046 -0.0432973 -0.150551 0.0387046 -0.0188558 -0.155514 0.0387046 -0.027129 -0.154286 0.0387046 -0.0277633 -0.157894 0.0371966 -0.0192967 -0.159151 0.0371966 -0.0184087 -0.151827 0.039724 -0.00210263 -0.156639 0.0387046 0.00630563 -0.156526 0.0387046 0.0146867 -0.155963 0.0387046 0.0230046 -0.154955 0.0387046 0.0312245 -0.15351 0.0387046 0.0393126 -0.15164 0.0387046 0.0461173 -0.145821 0.039724 0.0624801 -0.143654 0.0387046 0.069747 -0.14027 0.0387046 0.0898847 -0.1283 0.0387046 0.0834659 -0.132566 0.0387046 0.0854177 -0.135666 0.0371966 0.0814871 -0.129423 0.039724 0.107245 -0.114187 0.0387046 0.101782 -0.119083 0.0387046 0.104162 -0.121867 0.0371966 0.0993688 -0.11626 0.039724 0.109717 -0.106549 0.039724 0.117188 -0.103958 0.0387046 0.118783 -0.096338 0.039724 0.125825 -0.0933187 0.0387046 0.126591 -0.0858207 0.039724 0.130038 -0.0805022 0.039724 0.138657 -0.0645337 0.039724 0.144922 -0.0488679 0.039724 0.146542 -0.0437704 0.039724 0.147949 -0.0387507 0.039724 0.149154 -0.0338164 0.039724 0.152198 -0.015042 0.039724 0.15168 -0.0195827 0.039724 0.155364 -0.0200582 0.0387046 0.151008 -0.0242277 0.039724 0.15281 -0.00628253 0.039724 0.152925 -0.00206665 0.039724 0.165942 0.0214239 0.0328772 0.169169 0.0218405 0.0301473 0.165206 0.0265056 0.0328772 0.152925 0.00206665 0.039724 0.15281 0.00628253 0.039724 0.152571 0.010608 0.039724 0.152571 -0.010608 0.039724 0.152198 0.015042 0.039724 0.15168 0.0195827 0.039724 0.151008 0.0242277 0.039724 0.15017 0.0289737 0.039724 0.152776 0.0346376 0.0387046 0.147949 0.0387507 0.039724 0.146542 0.0437704 0.039724 0.144416 0.0606994 0.0387046 0.14655 0.0553467 0.0387046 0.149977 0.0566409 0.0371966 0.143076 0.0540345 0.039724 0.140992 0.0592603 0.039724 0.142024 0.0661008 0.0387046 0.136061 0.0698417 0.039724 0.136426 0.0769953 0.0387046 0.130038 0.0805022 0.039724 0.129665 0.0879048 0.0387046 0.122842 0.0911063 0.039724 0.117188 0.103958 0.0387046 0.109717 0.106549 0.039724 0.101782 0.119083 0.0387046 0.095993 0.123797 0.0387046 0.0834659 0.132566 0.0387046 0.0854177 0.135666 0.0371966 0.0814871 0.129423 0.039724 0.069747 0.14027 0.0387046 0.0624801 0.143654 0.0387046 0.0549687 0.146693 0.0387046 0.0472372 0.149362 0.0387046 0.0393126 0.15164 0.0387046 0.0230046 0.154955 0.0387046 0.0235426 0.158578 0.0371966 0.0224592 0.151281 0.039724 -0.00210263 0.156639 0.0387046 -0.0105018 0.156301 0.0387046 -0.0188558 0.155514 0.0387046 -0.027129 0.154286 0.0387046 -0.0352871 0.152627 0.0387046 -0.0587535 0.145218 0.0387046 -0.0511289 0.148075 0.0387046 -0.0523244 0.151537 0.0371966 -0.0499167 0.144564 0.039724 -0.0661455 0.142004 0.0387046 -0.0732821 0.138456 0.0387046 -0.0782436 0.131409 0.039724 -0.0867135 0.130465 0.0387046 -0.0929783 0.126077 0.0387046 -0.120127 0.111482 0.0352405 -0.124984 0.106007 0.0352405 -0.112103 0.104035 0.039724 -0.116636 0.0989267 0.039724 -0.120852 0.0937302 0.039724 -0.124755 0.0884689 0.039724 -0.128352 0.0831643 0.039724 -0.142064 0.0566407 0.039724 -0.143253 0.0633948 0.0387046 -0.145514 0.0580162 0.0387046 -0.137393 0.0671843 0.039724 -0.139857 0.0618918 0.039724 -0.134848 0.0797268 0.0387046 -0.15332 0.0321454 0.0387046 -0.154268 0.027234 0.0387046 -0.148576 0.0362725 0.039724 -0.147526 0.0526924 0.0387046 -0.149299 0.0474345 0.0387046 -0.149685 0.0313832 0.039724 -0.151364 0.0218924 0.039724 -0.151958 0.0172991 0.039724 -0.152402 0.0128115 0.039724 -0.155648 0.0177192 0.0387046 -0.156103 0.0131226 0.0387046 -0.152883 0.00416085 0.039724 -0.152707 0.00843162 0.039724 -0.17102 0 0.02973 -0.17318 0 0.027553 -0.170509 -0.00464057 0.0301473 -0.156415 -0.00863637 0.0387046 -0.167257 -0.00455206 0.0328772 -0.168723 0 0.031762 -0.162834 -0.0185373 0.0352405 -0.159288 -0.0181336 0.0371966 -0.16331 -0.0137285 0.0352405 -0.162198 -0.0234593 0.0352405 -0.158666 -0.0229483 0.0371966 -0.16139 -0.0284914 0.0352405 -0.156905 -0.032897 0.0371966 -0.157875 -0.0278708 0.0371966 -0.163758 -0.034334 0.0328772 -0.15921 -0.0388687 0.0352405 -0.160398 -0.0336295 0.0352405 -0.150848 -0.0422521 0.0387046 -0.154337 -0.0551252 0.0352405 -0.150975 -0.0539245 0.0371966 -0.156192 -0.0496245 0.0352405 -0.140729 -0.0688158 0.0387046 -0.14402 -0.0704249 0.0371966 -0.112423 -0.114291 0.0371966 -0.114926 -0.116836 0.0352405 -0.106999 -0.119384 0.0371966 -0.109854 -0.111679 0.0387046 -0.101241 -0.124305 0.0371966 -0.0887412 -0.133515 0.0371966 -0.090717 -0.136488 0.0352405 -0.0820177 -0.137748 0.0371966 -0.0867135 -0.130465 0.0387046 -0.0749957 -0.141693 0.0371966 -0.0676922 -0.145324 0.0371966 -0.0601274 -0.148614 0.0371966 -0.0523244 -0.151537 0.0371966 -0.0361122 -0.156196 0.0371966 -0.0369163 -0.159674 0.0352405 -0.0352871 -0.152627 0.0387046 -0.0107474 -0.159956 0.0371966 -0.0021518 -0.160302 0.0371966 0.00645308 -0.160187 0.0371966 0.0150301 -0.15961 0.0371966 0.0235426 -0.158578 0.0371966 0.0319546 -0.1571 0.0371966 0.0483418 -0.152854 0.0371966 0.0494182 -0.156258 0.0352405 0.0562541 -0.150123 0.0371966 0.0472372 -0.149362 0.0387046 0.0639411 -0.147013 0.0371966 0.071378 -0.14355 0.0371966 0.0767484 -0.136565 0.0387046 0.0919866 -0.131301 0.0371966 0.095993 -0.123797 0.0387046 0.115009 -0.111689 0.0371966 0.11757 -0.114175 0.0352405 0.119928 -0.106389 0.0371966 0.112381 -0.109137 0.0387046 0.121668 -0.0986774 0.0387046 0.132697 -0.0899603 0.0371966 0.135652 -0.0919633 0.0352405 0.13631 -0.0843852 0.0371966 0.129665 -0.0879048 0.0387046 0.133196 -0.0824571 0.0387046 0.139616 -0.0787958 0.0371966 0.139365 -0.0715378 0.0387046 0.142024 -0.0661008 0.0387046 0.151912 -0.051225 0.0371966 0.149977 -0.0566409 0.0371966 0.153317 -0.0579021 0.0352405 0.14655 -0.0553467 0.0387046 0.148441 -0.0500546 0.0387046 0.150101 -0.0448333 0.0387046 0.151542 -0.0396918 0.0387046 0.152776 -0.0346376 0.0387046 0.153817 -0.0296773 0.0387046 0.154675 -0.024816 0.0387046 0.155894 -0.0154073 0.0387046 0.156276 -0.0108656 0.0387046 0.156521 -0.00643509 0.0387046 0.156639 -0.00211684 0.0387046 0.156639 0.00211684 0.0387046 0.156521 0.00643509 0.0387046 0.156276 0.0108656 0.0387046 0.155894 0.0154073 0.0387046 0.155364 0.0200582 0.0387046 0.154675 0.024816 0.0387046 0.153817 0.0296773 0.0387046 0.155085 0.0406199 0.0371966 0.158538 0.0415243 0.0352405 0.153611 0.0458817 0.0371966 0.151542 0.0396918 0.0387046 0.150101 0.0448333 0.0387046 0.148441 0.0500546 0.0387046 0.145346 0.0676465 0.0371966 0.139365 0.0715378 0.0387046 0.139616 0.0787958 0.0371966 0.133196 0.0824571 0.0387046 0.132697 0.0899603 0.0371966 0.125825 0.0933187 0.0387046 0.124513 0.100985 0.0371966 0.119928 0.106389 0.0371966 0.112381 0.109137 0.0387046 0.109753 0.116857 0.0371966 0.104162 0.121867 0.0371966 0.0919866 0.131301 0.0371966 0.0940347 0.134224 0.0352405 0.0898847 0.1283 0.0387046 0.0785431 0.139758 0.0371966 0.071378 0.14355 0.0371966 0.0639411 0.147013 0.0371966 0.0562541 0.150123 0.0371966 0.0402319 0.155186 0.0371966 0.0411277 0.158642 0.0352405 0.0319546 0.1571 0.0371966 0.0326661 0.160597 0.0352405 0.0312245 0.15351 0.0387046 0.0150301 0.15961 0.0371966 0.00645308 0.160187 0.0371966 -0.0021518 0.160302 0.0371966 -0.0107474 0.159956 0.0371966 -0.0192967 0.159151 0.0371966 -0.0277633 0.157894 0.0371966 -0.0443097 0.154072 0.0371966 -0.0452963 0.157502 0.0352405 -0.0432973 0.150551 0.0387046 -0.0601274 0.148614 0.0371966 -0.0676922 0.145324 0.0371966 -0.0820177 0.137748 0.0371966 -0.0838439 0.140815 0.0352405 -0.0887412 0.133515 0.0371966 -0.0801436 0.1346 0.0387046 -0.101241 0.124305 0.0371966 -0.103495 0.127072 0.0352405 -0.0989277 0.121464 0.0387046 -0.119468 0.101329 0.0387046 -0.123786 0.0960064 0.0387046 -0.127784 0.0906172 0.0387046 -0.131469 0.0851839 0.0387046 -0.137931 0.074265 0.0387046 -0.140729 0.0688158 0.0387046 -0.15279 0.0485437 0.0371966 -0.150848 0.0422521 0.0387046 -0.138001 0.0815911 0.0371966 -0.152184 0.0371533 0.0387046 -0.150975 0.0539245 0.0371966 -0.15504 0.022424 0.0387046 -0.157875 0.0278708 0.0371966 -0.159288 0.0181336 0.0371966 -0.159753 0.0134295 0.0371966 -0.156415 0.00863637 0.0387046 -0.156595 0.00426189 0.0387046 -0.160073 -0.00883832 0.0371966 -0.159753 -0.0134295 0.0371966 -0.155742 -0.0380221 0.0371966 -0.157812 -0.0442028 0.0352405 -0.162545 -0.0396829 0.0328772 -0.152233 -0.0606948 0.0352405 -0.15757 -0.0562799 0.0328772 -0.155421 -0.0619662 0.0328772 -0.149867 -0.0663217 0.0352405 -0.153006 -0.067711 0.0328772 -0.141156 -0.0760016 0.0371966 -0.144299 -0.0776938 0.0352405 -0.141074 -0.0834078 0.0352405 -0.124984 -0.106007 0.0352405 -0.11751 -0.109054 0.0371966 -0.109382 -0.122042 0.0352405 -0.0972711 -0.131898 0.0352405 -0.0993087 -0.13466 0.0328772 -0.0951525 -0.129025 0.0371966 -0.0838439 -0.140815 0.0352405 -0.0766656 -0.144848 0.0352405 -0.0691994 -0.14856 0.0352405 -0.0534895 -0.154911 0.0352405 -0.0546099 -0.158156 0.0328772 -0.0452963 -0.157502 0.0352405 -0.0462451 -0.160801 0.0328772 -0.0443097 -0.154072 0.0371966 -0.0283815 -0.16141 0.0352405 -0.0197263 -0.162694 0.0352405 -0.0109867 -0.163517 0.0352405 -0.00219971 -0.163871 0.0352405 0.00659676 -0.163753 0.0352405 0.0153648 -0.163164 0.0352405 0.0240668 -0.162109 0.0352405 0.0411277 -0.158642 0.0352405 0.0419892 -0.161965 0.0328772 0.0402319 -0.155186 0.0371966 0.0575066 -0.153465 0.0352405 0.0653648 -0.150287 0.0352405 0.0802918 -0.14287 0.0352405 0.0819738 -0.145863 0.0328772 0.0873196 -0.138686 0.0352405 0.0785431 -0.139758 0.0371966 0.0940347 -0.134224 0.0352405 0.0982376 -0.126692 0.0371966 0.106481 -0.124581 0.0352405 0.109753 -0.116857 0.0371966 0.127285 -0.103233 0.0352405 0.129951 -0.105396 0.0328772 0.131634 -0.0976272 0.0352405 0.124513 -0.100985 0.0371966 0.128767 -0.0955008 0.0371966 0.142724 -0.0805502 0.0352405 0.142624 -0.0732106 0.0371966 0.145346 -0.0676465 0.0371966 0.147793 -0.0621188 0.0371966 0.153611 -0.0458817 0.0371966 0.155085 -0.0406199 0.0371966 0.156348 -0.0354476 0.0371966 0.157413 -0.0303712 0.0371966 0.158292 -0.0253963 0.0371966 0.158997 -0.0205273 0.0371966 0.159539 -0.0157675 0.0371966 0.15993 -0.0111197 0.0371966 0.160181 -0.00658557 0.0371966 0.160302 -0.00216634 0.0371966 0.160302 0.00216634 0.0371966 0.160181 0.00658557 0.0371966 0.15993 0.0111197 0.0371966 0.159539 0.0157675 0.0371966 0.158997 0.0205273 0.0371966 0.158292 0.0253963 0.0371966 0.157413 0.0303712 0.0371966 0.156348 0.0354476 0.0371966 0.151912 0.051225 0.0371966 0.153317 0.0579021 0.0352405 0.147793 0.0621188 0.0371966 0.1458 0.0748407 0.0352405 0.148854 0.0764084 0.0328772 0.142724 0.0805502 0.0352405 0.142624 0.0732106 0.0371966 0.139345 0.0862641 0.0352405 0.142264 0.0880711 0.0328772 0.135652 0.0919633 0.0352405 0.13631 0.0843852 0.0371966 0.128767 0.0955008 0.0371966 0.127285 0.103233 0.0352405 0.11757 0.114175 0.0352405 0.120032 0.116567 0.0328772 0.112197 0.119459 0.0352405 0.115009 0.111689 0.0371966 0.106481 0.124581 0.0352405 0.0982376 0.126692 0.0371966 0.0873196 0.138686 0.0352405 0.0802918 0.14287 0.0352405 0.0729673 0.146746 0.0352405 0.0653648 0.150287 0.0352405 0.0494182 0.156258 0.0352405 0.0504533 0.159531 0.0328772 0.0483418 0.152854 0.0371966 0.0240668 0.162109 0.0352405 0.0153648 0.163164 0.0352405 0.00659676 0.163753 0.0352405 -0.00219971 0.163871 0.0352405 -0.0109867 0.163517 0.0352405 -0.0197263 0.162694 0.0352405 -0.0369163 0.159674 0.0352405 -0.0376896 0.163019 0.0328772 -0.0361122 0.156196 0.0371966 -0.0534895 0.154911 0.0352405 -0.0614661 0.151923 0.0352405 -0.0691994 0.14856 0.0352405 -0.0749957 0.141693 0.0371966 -0.090717 0.136488 0.0352405 -0.0951525 0.129025 0.0371966 -0.109382 0.122042 0.0352405 -0.122262 0.103699 0.0371966 -0.126681 0.0982514 0.0371966 -0.130772 0.0927362 0.0371966 -0.134543 0.0871758 0.0371966 -0.141156 0.0760016 0.0371966 -0.146603 0.0648772 0.0371966 -0.148917 0.0593728 0.0371966 -0.141074 0.0834078 0.0352405 -0.159464 0.050664 0.0328772 -0.156192 0.0496245 0.0352405 -0.15757 0.0562799 0.0328772 -0.154375 0.0432401 0.0371966 -0.155742 0.0380221 0.0371966 -0.154337 0.0551252 0.0352405 -0.156905 0.032897 0.0371966 -0.158666 0.0229483 0.0371966 -0.16139 0.0284914 0.0352405 -0.162834 0.0185373 0.0352405 -0.16331 0.0137285 0.0352405 -0.160257 0.00436155 0.0371966 -0.160073 0.00883832 0.0371966 -0.166295 0 0.0336348 -0.163637 -0.00903511 0.0352405 -0.176305 -0.0047983 0.0237508 -0.17354 -0.00472304 0.0270916 -0.175197 0 0.0252429 -0.169478 -0.0192936 0.0301473 -0.172994 -0.0145426 0.0270916 -0.17249 -0.0196365 0.0270916 -0.168816 -0.0244164 0.0301473 -0.165596 -0.0239507 0.0328772 -0.162565 -0.0516492 0.0301473 -0.159464 -0.050664 0.0328772 -0.164251 -0.0460063 0.0301473 -0.147226 -0.071993 0.0352405 -0.147322 -0.0793213 0.0328772 -0.15031 -0.073501 0.0328772 -0.153233 -0.0749303 0.0301473 -0.132214 -0.102543 0.0328772 -0.122643 -0.113817 0.0328772 -0.125028 -0.11603 0.0301473 -0.117334 -0.119283 0.0328772 -0.120127 -0.111482 0.0352405 -0.111673 -0.124598 0.0328772 -0.103495 -0.127072 0.0352405 -0.0926173 -0.139347 0.0328772 -0.0856002 -0.143765 0.0328772 -0.0782715 -0.147882 0.0328772 -0.0627537 -0.155105 0.0328772 -0.063974 -0.158121 0.0301473 -0.0614661 -0.151923 0.0352405 -0.0376896 -0.163019 0.0328772 -0.028976 -0.164791 0.0328772 -0.0201396 -0.166103 0.0328772 -0.0112168 -0.166943 0.0328772 -0.00224579 -0.167304 0.0328772 0.00673495 -0.167183 0.0328772 0.0156866 -0.166582 0.0328772 0.0333504 -0.163962 0.0328772 0.0339989 -0.16715 0.0301473 0.0326661 -0.160597 0.0352405 0.0504533 -0.159531 0.0328772 0.0587112 -0.15668 0.0328772 0.066734 -0.153435 0.0328772 0.0729673 -0.146746 0.0352405 0.0891487 -0.141592 0.0328772 0.102529 -0.132225 0.0328772 0.104522 -0.134797 0.0301473 0.108712 -0.127191 0.0328772 0.100425 -0.129512 0.0352405 0.112197 -0.119459 0.0352405 0.120032 -0.116567 0.0328772 0.122598 -0.108758 0.0352405 0.138493 -0.0938897 0.0328772 0.139345 -0.0862641 0.0352405 0.151694 -0.0706013 0.0328772 0.148854 -0.0764084 0.0328772 0.151748 -0.0778942 0.0301473 0.1458 -0.0748407 0.0352405 0.148582 -0.0691527 0.0352405 0.151083 -0.0635019 0.0352405 0.156528 -0.059115 0.0328772 0.155295 -0.0523656 0.0352405 0.157031 -0.0469032 0.0352405 0.158538 -0.0415243 0.0352405 0.15983 -0.0362368 0.0352405 0.160918 -0.0310475 0.0352405 0.161817 -0.0259618 0.0352405 0.162537 -0.0209843 0.0352405 0.163091 -0.0161186 0.0352405 0.163491 -0.0113673 0.0352405 0.163748 -0.0067322 0.0352405 0.163871 -0.00221457 0.0352405 0.163871 0.00221457 0.0352405 0.163748 0.0067322 0.0352405 0.163491 0.0113673 0.0352405 0.163091 0.0161186 0.0352405 0.162537 0.0209843 0.0352405 0.161817 0.0259618 0.0352405 0.160918 0.0310475 0.0352405 0.15983 0.0362368 0.0352405 0.161859 0.0423942 0.0328772 0.157031 0.0469032 0.0352405 0.155295 0.0523656 0.0352405 0.156528 0.059115 0.0328772 0.151083 0.0635019 0.0352405 0.148582 0.0691527 0.0352405 0.134392 0.0996722 0.0328772 0.137005 0.10161 0.0301473 0.129951 0.105396 0.0328772 0.131634 0.0976272 0.0352405 0.122598 0.108758 0.0352405 0.114547 0.121961 0.0328772 0.102529 0.132225 0.0328772 0.104522 0.134797 0.0301473 0.0960045 0.137036 0.0328772 0.100425 0.129512 0.0352405 0.0891487 0.141592 0.0328772 0.0819738 0.145863 0.0328772 0.0744957 0.14982 0.0328772 0.0587112 0.15668 0.0328772 0.0598529 0.159727 0.0301473 0.0575066 0.153465 0.0352405 0.0419892 0.161965 0.0328772 0.0333504 0.163962 0.0328772 0.0245709 0.165505 0.0328772 0.0156866 0.166582 0.0328772 0.00673495 0.167183 0.0328772 -0.00224579 0.167304 0.0328772 -0.0112168 0.166943 0.0328772 -0.028976 0.164791 0.0328772 -0.0295395 0.167995 0.0301473 -0.0283815 0.16141 0.0352405 -0.0462451 0.160801 0.0328772 -0.0546099 0.158156 0.0328772 -0.0627537 0.155105 0.0328772 -0.0782715 0.147882 0.0328772 -0.0797935 0.150758 0.0301473 -0.0856002 0.143765 0.0328772 -0.0766656 0.144848 0.0352405 -0.0926173 0.139347 0.0328772 -0.0972711 0.131898 0.0352405 -0.105663 0.129734 0.0328772 -0.117334 0.119283 0.0328772 -0.119615 0.121603 0.0301473 -0.129501 0.100439 0.0352405 -0.133684 0.094801 0.0352405 -0.111673 0.124598 0.0328772 -0.137538 0.0891168 0.0352405 -0.144029 0.0851549 0.0328772 -0.149867 0.0663217 0.0352405 -0.152233 0.0606948 0.0352405 -0.157812 0.0442028 0.0352405 -0.15921 0.0388687 0.0352405 -0.160398 0.0336295 0.0352405 -0.162198 0.0234593 0.0352405 -0.166731 0.0140161 0.0328772 -0.163637 0.00903511 0.0352405 -0.166245 0.0189256 0.0328772 -0.163825 0.00445866 0.0352405 -0.178762 -0.00486518 0.0201657 -0.177063 0 0.0228092 -0.178769 0 0.020261 -0.167065 -0.00922437 0.0328772 -0.166731 -0.0140161 0.0328772 -0.166245 -0.0189256 0.0328772 -0.164771 -0.0290882 0.0328772 -0.17096 -0.0301808 0.0270916 -0.166943 -0.0350016 0.0301473 -0.167975 -0.0296538 0.0301473 -0.165706 -0.0404546 0.0301473 -0.16991 -0.0356236 0.0270916 -0.161118 -0.0451288 0.0328772 -0.160634 -0.0573743 0.0301473 -0.158444 -0.0631711 0.0301473 -0.163488 -0.058394 0.0270916 -0.16126 -0.0642938 0.0270916 -0.150187 -0.0808637 0.0301473 -0.134785 -0.104537 0.0301473 -0.127602 -0.108228 0.0328772 -0.119615 -0.121603 0.0301473 -0.10124 -0.137279 0.0301473 -0.107718 -0.132257 0.0301473 -0.109632 -0.134607 0.0270916 -0.105663 -0.129734 0.0328772 -0.0944183 -0.142057 0.0301473 -0.0872647 -0.14656 0.0301473 -0.0720228 -0.154621 0.0301473 -0.0733028 -0.157369 0.0270916 -0.070649 -0.151672 0.0328772 -0.0556719 -0.161232 0.0301473 -0.0471444 -0.163928 0.0301473 -0.0384224 -0.166189 0.0301473 -0.0295395 -0.167995 0.0301473 -0.0205312 -0.169332 0.0301473 -0.0114349 -0.170189 0.0301473 -0.00228946 -0.170557 0.0301473 0.0159917 -0.169821 0.0301473 0.0162759 -0.172839 0.0270916 0.0250487 -0.168723 0.0301473 0.0254939 -0.171722 0.0270916 0.0245709 -0.165505 0.0328772 0.0428057 -0.165114 0.0301473 0.0514344 -0.162633 0.0301473 0.0598529 -0.159727 0.0301473 0.0759443 -0.152733 0.0301473 0.077294 -0.155448 0.0270916 0.0835678 -0.148699 0.0301473 0.0744957 -0.14982 0.0328772 0.0908822 -0.144345 0.0301473 0.0960045 -0.137036 0.0328772 0.110826 -0.129664 0.0301473 0.114547 -0.121961 0.0328772 0.122366 -0.118834 0.0301473 0.125166 -0.111036 0.0328772 0.132478 -0.107445 0.0301473 0.134392 -0.0996722 0.0328772 0.141186 -0.0957154 0.0301473 0.142264 -0.0880711 0.0328772 0.145714 -0.0822375 0.0328772 0.154248 -0.0648321 0.0328772 0.163438 -0.0488169 0.0301473 0.161631 -0.0545021 0.0301473 0.164503 -0.0554707 0.0270916 0.158548 -0.0534625 0.0328772 0.16032 -0.0478857 0.0328772 0.161859 -0.0423942 0.0328772 0.163178 -0.0369959 0.0328772 0.164289 -0.0316978 0.0328772 0.165206 -0.0265056 0.0328772 0.165942 -0.0214239 0.0328772 0.166508 -0.0164563 0.0328772 0.166916 -0.0116054 0.0328772 0.167178 -0.00687322 0.0328772 0.167304 -0.00226096 0.0328772 0.167304 0.00226096 0.0328772 0.167178 0.00687322 0.0328772 0.166916 0.0116054 0.0328772 0.166508 0.0164563 0.0328772 0.164289 0.0316978 0.0328772 0.163178 0.0369959 0.0328772 0.161631 0.0545021 0.0301473 0.163438 0.0488169 0.0301473 0.166342 0.0496845 0.0270916 0.16032 0.0478857 0.0328772 0.158548 0.0534625 0.0328772 0.154644 0.0719741 0.0301473 0.157247 0.0660928 0.0301473 0.160042 0.0672673 0.0270916 0.154248 0.0648321 0.0328772 0.151694 0.0706013 0.0328772 0.151748 0.0778942 0.0301473 0.145714 0.0822375 0.0328772 0.145031 0.0897837 0.0301473 0.138493 0.0938897 0.0328772 0.132478 0.107445 0.0301473 0.125166 0.111036 0.0328772 0.122366 0.118834 0.0301473 0.116775 0.124333 0.0301473 0.108712 0.127191 0.0328772 0.0978714 0.1397 0.0301473 0.0908822 0.144345 0.0301473 0.0835678 0.148699 0.0301473 0.0680317 0.156418 0.0301473 0.0692407 0.159198 0.0270916 0.066734 0.153435 0.0328772 0.0514344 0.162633 0.0301473 0.0428057 0.165114 0.0301473 0.0339989 0.16715 0.0301473 0.0250487 0.168723 0.0301473 0.0159917 0.169821 0.0301473 0.00686591 0.170434 0.0301473 -0.00228946 0.170557 0.0301473 -0.0205312 0.169332 0.0301473 -0.0208961 0.172342 0.0270916 -0.0201396 0.166103 0.0328772 -0.0384224 0.166189 0.0301473 -0.0471444 0.163928 0.0301473 -0.0556719 0.161232 0.0301473 -0.063974 0.158121 0.0301473 -0.070649 0.151672 0.0328772 -0.0872647 0.14656 0.0301473 -0.107718 0.132257 0.0301473 -0.10124 0.137279 0.0301473 -0.103039 0.139719 0.0270916 -0.0993087 0.13466 0.0328772 -0.136484 0.0967869 0.0328772 -0.113845 0.127021 0.0301473 -0.14042 0.0909836 0.0328772 -0.15031 0.073501 0.0328772 -0.153006 0.067711 0.0328772 -0.155421 0.0619662 0.0328772 -0.162545 0.0396829 0.0328772 -0.161118 0.0451288 0.0328772 -0.164251 0.0460063 0.0301473 -0.162565 0.0516492 0.0301473 -0.160634 0.0573743 0.0301473 -0.164771 0.0290882 0.0328772 -0.163758 0.034334 0.0328772 -0.165596 0.0239507 0.0328772 -0.167975 0.0296538 0.0301473 -0.169478 0.0192936 0.0301473 -0.169973 0.0142886 0.0301473 -0.167065 0.00922437 0.0328772 -0.167257 0.00455206 0.0328772 -0.170313 -0.00940375 0.0301473 -0.169973 -0.0142886 0.0301473 -0.175238 -0.0199494 0.0237508 -0.1782 -0.0149802 0.0201657 -0.177681 -0.0202275 0.0201657 -0.16717 -0.0468239 0.0270916 -0.168651 -0.0411735 0.0270916 -0.171338 -0.0418296 0.0237508 -0.16809 -0.0534047 0.0237508 -0.165454 -0.0525671 0.0270916 -0.169834 -0.04757 0.0237508 -0.155981 -0.0690277 0.0301473 -0.158753 -0.0702544 0.0270916 -0.163829 -0.0653183 0.0237508 -0.161283 -0.0713739 0.0237508 -0.145694 -0.0944012 0.0270916 -0.139138 -0.0986689 0.0301473 -0.130084 -0.110333 0.0301473 -0.12725 -0.118092 0.0270916 -0.121741 -0.123764 0.0270916 -0.113845 -0.127021 0.0301473 -0.103039 -0.139719 0.0270916 -0.0960963 -0.144582 0.0270916 -0.0825056 -0.155882 0.0237508 -0.0812116 -0.153437 0.0270916 -0.0797935 -0.150758 0.0301473 -0.0651109 -0.160931 0.0270916 -0.0566612 -0.164097 0.0270916 -0.0479822 -0.166841 0.0270916 -0.0391053 -0.169142 0.0270916 -0.0300645 -0.170981 0.0270916 -0.0208961 -0.172342 0.0270916 -0.0116382 -0.173213 0.0270916 0.00709928 -0.176227 0.0237508 0.00698793 -0.173463 0.0270916 0.00686591 -0.170434 0.0301473 0.0346031 -0.17012 0.0270916 0.0435664 -0.168049 0.0270916 0.0523485 -0.165523 0.0270916 0.070344 -0.161735 0.0237508 0.0692407 -0.159198 0.0270916 0.0680317 -0.156418 0.0301473 0.0850529 -0.151342 0.0270916 0.10638 -0.137192 0.0270916 0.0996107 -0.142183 0.0270916 0.101198 -0.144449 0.0237508 0.0978714 -0.1397 0.0301473 0.124541 -0.120946 0.0270916 0.11885 -0.126543 0.0270916 0.120744 -0.128559 0.0237508 0.116775 -0.124333 0.0301473 0.1276 -0.113195 0.0301473 0.134833 -0.109355 0.0270916 0.137005 -0.10161 0.0301473 0.151188 -0.0853266 0.0270916 0.147608 -0.0913793 0.0270916 0.14996 -0.0928354 0.0237508 0.145031 -0.0897837 0.0301473 0.148548 -0.0838367 0.0301473 0.154445 -0.0792785 0.0270916 0.154644 -0.0719741 0.0301473 0.157247 -0.0660928 0.0301473 0.159572 -0.0602645 0.0301473 0.165007 -0.0432185 0.0301473 0.166351 -0.0377153 0.0301473 0.167484 -0.0323142 0.0301473 0.168419 -0.027021 0.0301473 0.169169 -0.0218405 0.0301473 0.169746 -0.0167762 0.0301473 0.170162 -0.0118311 0.0301473 0.170429 -0.00700687 0.0301473 0.170557 -0.00230493 0.0301473 0.170557 0.00230493 0.0301473 0.170429 0.00700687 0.0301473 0.170162 0.0118311 0.0301473 0.169746 0.0167762 0.0301473 0.17046 0.0328885 0.0270916 0.171412 0.0275013 0.0270916 0.174143 0.0279395 0.0237508 0.168419 0.027021 0.0301473 0.167484 0.0323142 0.0301473 0.166351 0.0377153 0.0301473 0.165007 0.0432185 0.0301473 0.159572 0.0602645 0.0301473 0.154445 0.0792785 0.0270916 0.148548 0.0838367 0.0301473 0.147608 0.0913793 0.0270916 0.141186 0.0957154 0.0301473 0.13944 0.103416 0.0270916 0.124541 0.120946 0.0270916 0.129868 0.115207 0.0270916 0.131937 0.117043 0.0237508 0.1276 0.113195 0.0301473 0.10638 0.137192 0.0270916 0.112795 0.131968 0.0270916 0.114592 0.134071 0.0237508 0.110826 0.129664 0.0301473 0.0996107 0.142183 0.0270916 0.0924973 0.14691 0.0270916 0.077294 0.155448 0.0270916 0.0785256 0.157925 0.0237508 0.0759443 0.152733 0.0301473 0.0609166 0.162565 0.0270916 0.0523485 0.165523 0.0270916 0.0435664 0.168049 0.0270916 0.0346031 0.17012 0.0270916 0.0254939 0.171722 0.0270916 0.0162759 0.172839 0.0270916 -0.00236728 0.176354 0.0237508 -0.0116382 0.173213 0.0270916 -0.00233015 0.173588 0.0270916 -0.0118236 0.175973 0.0237508 -0.0114349 0.170189 0.0301473 -0.0300645 0.170981 0.0270916 -0.0391053 0.169142 0.0270916 -0.0479822 0.166841 0.0270916 -0.0566612 0.164097 0.0270916 -0.0812116 0.153437 0.0270916 -0.0733028 0.157369 0.0270916 -0.0744708 0.159877 0.0237508 -0.0720228 0.154621 0.0301473 -0.0888156 0.149165 0.0270916 -0.0944183 0.142057 0.0301473 -0.109632 0.134607 0.0270916 -0.121741 0.123764 0.0270916 -0.134505 0.114083 0.0237508 -0.139138 0.0986689 0.0301473 -0.115868 0.129279 0.0270916 -0.14315 0.0927528 0.0301473 -0.165454 0.0525671 0.0270916 -0.163488 0.058394 0.0270916 -0.166094 0.0593244 0.0237508 -0.153233 0.0749303 0.0301473 -0.155981 0.0690277 0.0301473 -0.158444 0.0631711 0.0301473 -0.165706 0.0404546 0.0301473 -0.17096 0.0301808 0.0270916 -0.171816 0.0248504 0.0270916 -0.168816 0.0244164 0.0301473 -0.166943 0.0350016 0.0301473 -0.17249 0.0196365 0.0270916 -0.172994 0.0145426 0.0270916 -0.170509 0.00464057 0.0301473 -0.170313 0.00940375 0.0301473 -0.182582 -0.00496914 0.0124252 -0.182802 0 0.0120091 -0.183732 0 0.00908708 -0.17334 -0.00957087 0.0270916 -0.181653 0 0.0148524 -0.180869 -0.00492252 0.0163769 -0.171816 -0.0248504 0.0270916 -0.176987 -0.0255982 0.0201657 -0.174554 -0.0252463 0.0237508 -0.176105 -0.0310891 0.0201657 -0.172617 -0.0361913 0.0237508 -0.173685 -0.0306617 0.0237508 -0.168409 -0.0601513 0.0201657 -0.166094 -0.0593244 0.0237508 -0.170433 -0.0541491 0.0201657 -0.155957 -0.0762619 0.0270916 -0.158442 -0.0774771 0.0237508 -0.13638 -0.115673 0.0201657 -0.129278 -0.119974 0.0237508 -0.134505 -0.114083 0.0237508 -0.132395 -0.112293 0.0270916 -0.119355 -0.133169 0.0201657 -0.111379 -0.136752 0.0237508 -0.117714 -0.131339 0.0237508 -0.115868 -0.129279 0.0270916 -0.104681 -0.141945 0.0237508 -0.0976275 -0.146885 0.0237508 -0.0888156 -0.149165 0.0270916 -0.0744708 -0.159877 0.0237508 -0.0661484 -0.163496 0.0237508 -0.0575641 -0.166712 0.0237508 -0.0487468 -0.1695 0.0237508 -0.0397284 -0.171837 0.0237508 -0.0305435 -0.173705 0.0237508 -0.0119884 -0.178426 0.0201657 -0.00236728 -0.176354 0.0237508 -0.0118236 -0.175973 0.0237508 -0.00240027 -0.178812 0.0201657 -0.00233015 -0.173588 0.0270916 0.0165352 -0.175593 0.0237508 0.0259001 -0.174458 0.0237508 0.0351545 -0.172831 0.0237508 0.0442606 -0.170726 0.0237508 0.0531826 -0.168161 0.0237508 0.0609166 -0.162565 0.0270916 0.0785256 -0.157925 0.0237508 0.0864082 -0.153753 0.0237508 0.0924973 -0.14691 0.0270916 0.108075 -0.139378 0.0237508 0.112795 -0.131968 0.0270916 0.136981 -0.111097 0.0237508 0.131937 -0.117043 0.0237508 0.133776 -0.118674 0.0201657 0.129868 -0.115207 0.0270916 0.145985 -0.0989687 0.0237508 0.141662 -0.105064 0.0237508 0.143636 -0.106528 0.0201657 0.13944 -0.103416 0.0270916 0.143695 -0.0974165 0.0270916 0.162592 -0.0683392 0.0237508 0.1599 -0.0744205 0.0237508 0.162129 -0.0754578 0.0201657 0.157392 -0.0732532 0.0270916 0.160042 -0.0672673 0.0270916 0.162408 -0.0613355 0.0270916 0.170615 -0.0446875 0.0237508 0.168993 -0.0504761 0.0237508 0.171348 -0.0511797 0.0201657 0.166342 -0.0496845 0.0270916 0.167939 -0.0439866 0.0270916 0.169307 -0.0383856 0.0270916 0.17046 -0.0328885 0.0270916 0.171412 -0.0275013 0.0270916 0.172175 -0.0222286 0.0270916 0.172762 -0.0170744 0.0270916 0.173186 -0.0120413 0.0270916 0.173457 -0.0071314 0.0270916 0.173588 -0.00234589 0.0270916 0.173588 0.00234589 0.0270916 0.173457 0.0071314 0.0270916 0.173186 0.0120413 0.0270916 0.172762 0.0170744 0.0270916 0.172175 0.0222286 0.0270916 0.169307 0.0383856 0.0270916 0.167939 0.0439866 0.0270916 0.168993 0.0504761 0.0237508 0.164503 0.0554707 0.0270916 0.162408 0.0613355 0.0270916 0.162592 0.0683392 0.0237508 0.157392 0.0732532 0.0270916 0.14996 0.0928354 0.0237508 0.153597 0.0866862 0.0237508 0.155738 0.0878945 0.0201657 0.151188 0.0853266 0.0270916 0.143695 0.0974165 0.0270916 0.141662 0.105064 0.0237508 0.134833 0.109355 0.0270916 0.126526 0.122873 0.0237508 0.11885 0.126543 0.0270916 0.108075 0.139378 0.0237508 0.101198 0.144449 0.0237508 0.0876125 0.155896 0.0201657 0.0864082 0.153753 0.0237508 0.0850529 0.151342 0.0270916 0.070344 0.161735 0.0237508 0.0618873 0.165156 0.0237508 0.0531826 0.168161 0.0237508 0.0442606 0.170726 0.0237508 0.0351545 0.172831 0.0237508 0.0259001 0.174458 0.0237508 0.00719823 0.178684 0.0201657 0.00709928 0.176227 0.0237508 0.00698793 0.173463 0.0270916 -0.021229 0.175088 0.0237508 -0.0305435 0.173705 0.0237508 -0.0397284 0.171837 0.0237508 -0.0487468 0.1695 0.0237508 -0.0670704 0.165775 0.0201657 -0.0661484 0.163496 0.0237508 -0.0651109 0.160931 0.0270916 -0.0825056 0.155882 0.0237508 -0.0902308 0.151542 0.0237508 -0.0960963 0.144582 0.0270916 -0.104681 0.141945 0.0237508 -0.111379 0.136752 0.0237508 -0.123681 0.125736 0.0237508 -0.12725 0.118092 0.0270916 -0.117714 0.131339 0.0237508 -0.145694 0.0944012 0.0270916 -0.152856 0.0823008 0.0270916 -0.155957 0.0762619 0.0270916 -0.158753 0.0702544 0.0270916 -0.16126 0.0642938 0.0270916 -0.16717 0.0468239 0.0270916 -0.168651 0.0411735 0.0270916 -0.16809 0.0534047 0.0237508 -0.16991 0.0356236 0.0270916 -0.173685 0.0306617 0.0237508 -0.175238 0.0199494 0.0237508 -0.17575 0.0147743 0.0237508 -0.17354 0.00472304 0.0270916 -0.17334 0.00957087 0.0270916 -0.176102 -0.00972337 0.0237508 -0.17575 -0.0147743 0.0237508 -0.173726 -0.0424126 0.0201657 -0.175023 -0.0366957 0.0201657 -0.177086 -0.0371282 0.0163769 -0.172201 -0.0482331 0.0201657 -0.175774 -0.0429124 0.0163769 -0.166113 -0.0662287 0.0201657 -0.163531 -0.0723687 0.0201657 -0.16807 -0.0670092 0.0163769 -0.165458 -0.0732215 0.0163769 -0.145873 -0.103445 0.0201657 -0.139366 -0.10809 0.0237508 -0.13108 -0.121646 0.0201657 -0.123681 -0.125736 0.0237508 -0.112932 -0.138658 0.0201657 -0.10614 -0.143923 0.0201657 -0.0925666 -0.155465 0.0163769 -0.0836556 -0.158055 0.0201657 -0.0914884 -0.153654 0.0201657 -0.0902308 -0.151542 0.0237508 -0.0755088 -0.162105 0.0201657 -0.0670704 -0.165775 0.0201657 -0.0583664 -0.169035 0.0201657 -0.0494262 -0.171862 0.0201657 -0.0313342 -0.178202 0.0163769 -0.0215249 -0.177528 0.0201657 -0.0309692 -0.176126 0.0201657 -0.0217786 -0.17962 0.0163769 -0.021229 -0.175088 0.0237508 0.00719823 -0.178684 0.0201657 0.0167657 -0.178041 0.0201657 0.0262611 -0.17689 0.0201657 0.0356445 -0.17524 0.0201657 0.0448775 -0.173106 0.0201657 0.0634893 -0.169431 0.0163769 0.0713245 -0.163989 0.0201657 0.0627498 -0.167458 0.0201657 0.0618873 -0.165156 0.0237508 0.0796201 -0.160126 0.0201657 0.0876125 -0.155896 0.0201657 0.0939712 -0.149251 0.0237508 0.102608 -0.146462 0.0201657 0.109581 -0.141321 0.0201657 0.114592 -0.134071 0.0237508 0.122427 -0.130351 0.0201657 0.126526 -0.122873 0.0237508 0.15205 -0.0941293 0.0201657 0.153597 -0.0866862 0.0237508 0.156906 -0.0805417 0.0237508 0.164996 -0.0623128 0.0237508 0.167125 -0.0563546 0.0237508 0.172005 -0.0389972 0.0237508 0.173176 -0.0334125 0.0237508 0.174143 -0.0279395 0.0237508 0.174918 -0.0225828 0.0237508 0.175515 -0.0173465 0.0237508 0.175945 -0.0122332 0.0237508 0.176221 -0.00724503 0.0237508 0.176354 -0.00238327 0.0237508 0.176354 0.00238327 0.0237508 0.176221 0.00724503 0.0237508 0.175945 0.0122332 0.0237508 0.175515 0.0173465 0.0237508 0.174918 0.0225828 0.0237508 0.174402 0.0395408 0.0201657 0.17559 0.0338783 0.0201657 0.177659 0.0342775 0.0163769 0.173176 0.0334125 0.0237508 0.172005 0.0389972 0.0237508 0.170615 0.0446875 0.0237508 0.167295 0.0631813 0.0201657 0.169454 0.0571401 0.0201657 0.171451 0.0578135 0.0163769 0.167125 0.0563546 0.0237508 0.164996 0.0623128 0.0237508 0.164039 0.076347 0.0163769 0.159093 0.0816643 0.0201657 0.162129 0.0754578 0.0201657 0.1599 0.0744205 0.0237508 0.156906 0.0805417 0.0237508 0.149764 0.101531 0.0163769 0.143636 0.106528 0.0201657 0.14802 0.100348 0.0201657 0.145985 0.0989687 0.0237508 0.136981 0.111097 0.0237508 0.133776 0.118674 0.0201657 0.123869 0.131887 0.0163769 0.11619 0.13594 0.0201657 0.122427 0.130351 0.0201657 0.120744 0.128559 0.0237508 0.109581 0.141321 0.0201657 0.102608 0.146462 0.0201657 0.0939712 0.149251 0.0237508 0.0796201 0.160126 0.0201657 0.0713245 0.163989 0.0201657 0.0627498 0.167458 0.0201657 0.0539239 0.170505 0.0201657 0.0448775 0.173106 0.0201657 0.0265706 0.178974 0.0163769 0.0167657 0.178041 0.0201657 0.0262611 0.17689 0.0201657 0.0169633 0.180139 0.0163769 0.0165352 0.175593 0.0237508 -0.00240027 0.178812 0.0201657 -0.0119884 0.178426 0.0201657 -0.0215249 0.177528 0.0201657 -0.0309692 0.176126 0.0201657 -0.0402821 0.174233 0.0201657 -0.0590543 0.171027 0.0163769 -0.0583664 0.169035 0.0201657 -0.0575641 0.166712 0.0237508 -0.0755088 0.162105 0.0201657 -0.0836556 0.158055 0.0201657 -0.100155 0.150688 0.0163769 -0.10614 0.143923 0.0201657 -0.0989883 0.148933 0.0201657 -0.0976275 0.146885 0.0237508 -0.120761 0.134739 0.0163769 -0.125405 0.127488 0.0201657 -0.119355 0.133169 0.0201657 -0.129278 0.119974 0.0237508 -0.13638 0.115673 0.0201657 -0.15575 0.0920851 0.0163769 -0.155291 0.0836122 0.0237508 -0.158442 0.0774771 0.0237508 -0.161283 0.0713739 0.0237508 -0.163829 0.0653183 0.0237508 -0.153936 0.0910126 0.0201657 -0.172617 0.0361913 0.0237508 -0.171338 0.0418296 0.0237508 -0.173726 0.0424126 0.0201657 -0.169834 0.04757 0.0237508 -0.170433 0.0541491 0.0201657 -0.168409 0.0601513 0.0201657 -0.174554 0.0252463 0.0237508 -0.176105 0.0310891 0.0201657 -0.177681 0.0202275 0.0201657 -0.1782 0.0149802 0.0201657 -0.176305 0.0047983 0.0237508 -0.176102 0.00972337 0.0237508 -0.180304 0 0.0176059 -0.178557 -0.0098589 0.0201657 -0.184656 -0.00502559 0.00419604 -0.183859 -0.00500389 0.00835136 -0.184423 0 0.0060991 -0.181477 -0.0206597 0.0124252 -0.18328 -0.0154073 0.00835136 -0.182746 -0.0208042 0.00835136 -0.182033 -0.026328 0.00835136 -0.180769 -0.0261452 0.0124252 -0.174075 -0.0553062 0.0124252 -0.172442 -0.0547872 0.0163769 -0.175881 -0.0492637 0.0124252 -0.170393 -0.0608602 0.0163769 -0.172007 -0.0614366 0.0124252 -0.15575 -0.0920851 0.0163769 -0.150079 -0.0972421 0.0201657 -0.147592 -0.104664 0.0163769 -0.141309 -0.109597 0.0201657 -0.137987 -0.117036 0.0163769 -0.132624 -0.12308 0.0163769 -0.125405 -0.127488 0.0201657 -0.120761 -0.134739 0.0163769 -0.114262 -0.140292 0.0163769 -0.101103 -0.152115 0.0124252 -0.100155 -0.150688 0.0163769 -0.0989883 -0.148933 0.0201657 -0.0846415 -0.159918 0.0163769 -0.0763986 -0.164015 0.0163769 -0.0678608 -0.167728 0.0163769 -0.0590543 -0.171027 0.0163769 -0.0411429 -0.177956 0.0124252 -0.0407568 -0.176286 0.0163769 -0.0402821 -0.174233 0.0201657 -0.0121297 -0.180529 0.0163769 -0.00242856 -0.18092 0.0163769 0.00728306 -0.180789 0.0163769 0.0169633 -0.180139 0.0163769 0.0265706 -0.178974 0.0163769 0.0360646 -0.177305 0.0163769 0.0550761 -0.174148 0.0124252 0.0545594 -0.172514 0.0163769 0.0539239 -0.170505 0.0201657 0.072165 -0.165922 0.0163769 0.0805584 -0.162013 0.0163769 0.097317 -0.154565 0.0124252 0.103818 -0.148188 0.0163769 0.0964039 -0.153115 0.0163769 0.095281 -0.151331 0.0201657 0.118672 -0.138844 0.0124252 0.123869 -0.131887 0.0163769 0.117559 -0.137542 0.0163769 0.11619 -0.13594 0.0201657 0.128289 -0.124585 0.0201657 0.135353 -0.120073 0.0163769 0.13889 -0.112646 0.0201657 0.145329 -0.107784 0.0163769 0.14802 -0.100348 0.0201657 0.153842 -0.0952386 0.0163769 0.155738 -0.0878945 0.0201657 0.159093 -0.0816643 0.0201657 0.164039 -0.076347 0.0163769 0.164858 -0.0692917 0.0201657 0.167295 -0.0631813 0.0201657 0.169454 -0.0571401 0.0201657 0.176458 -0.0400067 0.0163769 0.175032 -0.0458443 0.0163769 0.17669 -0.0462785 0.0124252 0.172993 -0.0453104 0.0201657 0.174402 -0.0395408 0.0201657 0.17559 -0.0338783 0.0201657 0.17657 -0.0283289 0.0201657 0.177357 -0.0228976 0.0201657 0.177961 -0.0175882 0.0201657 0.178398 -0.0124037 0.0201657 0.178678 -0.00734601 0.0201657 0.178812 -0.00241649 0.0201657 0.178812 0.00241649 0.0201657 0.178678 0.00734601 0.0201657 0.178398 0.0124037 0.0201657 0.177961 0.0175882 0.0201657 0.177357 0.0228976 0.0201657 0.17657 0.0283289 0.0201657 0.172993 0.0453104 0.0201657 0.171348 0.0511797 0.0201657 0.164858 0.0692917 0.0201657 0.157573 0.0889303 0.0163769 0.15205 0.0941293 0.0201657 0.141858 0.115053 0.0124252 0.135353 0.120073 0.0163769 0.140527 0.113973 0.0163769 0.13889 0.112646 0.0201657 0.128289 0.124585 0.0201657 0.117559 0.137542 0.0163769 0.110873 0.142986 0.0163769 0.097317 0.154565 0.0124252 0.088645 0.157734 0.0163769 0.0964039 0.153115 0.0163769 0.095281 0.151331 0.0201657 0.0805584 0.162013 0.0163769 0.072165 0.165922 0.0163769 0.0634893 0.169431 0.0163769 0.0545594 0.172514 0.0163769 0.0364061 0.178985 0.0124252 0.0360646 0.177305 0.0163769 0.0356445 0.17524 0.0201657 0.00728306 0.180789 0.0163769 -0.00242856 0.18092 0.0163769 -0.0121297 0.180529 0.0163769 -0.0217786 0.17962 0.0163769 -0.0313342 0.178202 0.0163769 -0.0504824 0.175535 0.0124252 -0.0500087 0.173888 0.0163769 -0.0494262 0.171862 0.0201657 -0.0678608 0.167728 0.0163769 -0.0763986 0.164015 0.0163769 -0.0846415 0.159918 0.0163769 -0.0914884 0.153654 0.0201657 -0.107391 0.14562 0.0163769 -0.112932 0.138658 0.0201657 -0.13388 0.124245 0.0124252 -0.137987 0.117036 0.0163769 -0.132624 0.12308 0.0163769 -0.13108 0.121646 0.0201657 -0.126883 0.128991 0.0163769 -0.157456 0.0847776 0.0201657 -0.16065 0.078557 0.0201657 -0.163531 0.0723687 0.0201657 -0.166113 0.0662287 0.0201657 -0.172201 0.0482331 0.0201657 -0.170393 0.0608602 0.0163769 -0.172442 0.0547872 0.0163769 -0.175023 0.0366957 0.0201657 -0.176987 0.0255982 0.0201657 -0.178181 0.0314555 0.0163769 -0.179775 0.0204659 0.0163769 -0.1803 0.0151568 0.0163769 -0.178762 0.00486518 0.0201657 -0.178557 0.0098589 0.0201657 -0.185 0 6.08402e-17 -0.184932 -0.00503308 3.33068e-17 -0.184852 0 0.00306329 -0.180661 -0.00997508 0.0163769 -0.1803 -0.0151568 0.0163769 -0.179775 -0.0204659 0.0163769 -0.179073 -0.0258999 0.0163769 -0.178181 -0.0314555 0.0163769 -0.181126 -0.0319754 0.00835136 -0.178763 -0.0374798 0.0124252 -0.179868 -0.0317534 0.0124252 -0.177438 -0.0433189 0.0124252 -0.180013 -0.0377419 0.00835136 -0.17423 -0.0488015 0.0163769 -0.169662 -0.0676438 0.0124252 -0.17321 -0.0618662 0.00835136 -0.170848 -0.0681168 0.00835136 -0.165947 -0.0811471 0.00419604 -0.154357 -0.100014 0.00835136 -0.14899 -0.105655 0.0124252 -0.153286 -0.09932 0.0124252 -0.151847 -0.0983881 0.0163769 -0.142974 -0.110888 0.0163769 -0.139294 -0.118144 0.0124252 -0.12898 -0.131123 0.00835136 -0.121905 -0.136015 0.0124252 -0.128084 -0.130212 0.0124252 -0.126883 -0.128991 0.0163769 -0.115345 -0.141621 0.0124252 -0.107391 -0.14562 0.0163769 -0.0934433 -0.156937 0.0124252 -0.0854432 -0.161432 0.0124252 -0.0771222 -0.165569 0.0124252 -0.0685035 -0.169317 0.0124252 -0.0508354 -0.176762 0.00835136 -0.0504824 -0.175535 0.0124252 -0.0500087 -0.173888 0.0163769 -0.031631 -0.17989 0.0124252 -0.0219848 -0.181322 0.0124252 -0.0122446 -0.182239 0.0124252 -0.00245156 -0.182633 0.0124252 0.00735204 -0.182502 0.0124252 0.0171239 -0.181845 0.0124252 0.0268222 -0.18067 0.0124252 0.046157 -0.178041 0.00835136 0.0458365 -0.176805 0.0124252 0.0454064 -0.175146 0.0163769 0.0640907 -0.171036 0.0124252 0.0728485 -0.167493 0.0124252 0.0813214 -0.163547 0.0124252 0.088645 -0.157734 0.0163769 0.104801 -0.149592 0.0124252 0.110873 -0.142986 0.0163769 0.125043 -0.133136 0.0124252 0.129801 -0.126054 0.0163769 0.140527 -0.113973 0.0163769 0.136635 -0.12121 0.0124252 0.146705 -0.108805 0.0124252 0.149764 -0.101531 0.0163769 0.160178 -0.0904003 0.00835136 0.162492 -0.0834093 0.0124252 0.159065 -0.0897726 0.0124252 0.157573 -0.0889303 0.0163769 0.160968 -0.0826267 0.0163769 0.169558 -0.0712672 0.00835136 0.17087 -0.0645314 0.0124252 0.168381 -0.0707723 0.0124252 0.166801 -0.0701083 0.0163769 0.169267 -0.0639259 0.0163769 0.171451 -0.0578135 0.0163769 0.173368 -0.0517828 0.0163769 0.177659 -0.0342775 0.0163769 0.178651 -0.0286627 0.0163769 0.179447 -0.0231674 0.0163769 0.180059 -0.0177955 0.0163769 0.1805 -0.0125499 0.0163769 0.180783 -0.00743258 0.0163769 0.180919 -0.00244497 0.0163769 0.180919 0.00244497 0.0163769 0.180783 0.00743258 0.0163769 0.1805 0.0125499 0.0163769 0.180059 0.0177955 0.0163769 0.179447 0.0231674 0.0163769 0.178651 0.0286627 0.0163769 0.179374 0.0406681 0.00835136 0.17669 0.0462785 0.0124252 0.178129 0.0403857 0.0124252 0.176458 0.0400067 0.0163769 0.175032 0.0458443 0.0163769 0.173368 0.0517828 0.0163769 0.173075 0.058361 0.0124252 0.169267 0.0639259 0.0163769 0.166801 0.0701083 0.0163769 0.160968 0.0826267 0.0163769 0.165593 0.0770701 0.0124252 0.159065 0.0897726 0.0124252 0.153842 0.0952386 0.0163769 0.145329 0.107784 0.0163769 0.151183 0.102492 0.0124252 0.136635 0.12121 0.0124252 0.129801 0.126054 0.0163769 0.125043 0.133136 0.0124252 0.118672 0.138844 0.0124252 0.105534 0.150638 0.00835136 0.104801 0.149592 0.0124252 0.103818 0.148188 0.0163769 0.0894846 0.159228 0.0124252 0.0813214 0.163547 0.0124252 0.0728485 0.167493 0.0124252 0.0554613 0.175366 0.00835136 0.0458365 0.176805 0.0124252 0.0550761 0.174148 0.0124252 0.046157 0.178041 0.00835136 0.0454064 0.175146 0.0163769 0.0268222 0.18067 0.0124252 0.0171239 0.181845 0.0124252 0.00735204 0.182502 0.0124252 -0.00245156 0.182633 0.0124252 -0.0122446 0.182239 0.0124252 -0.0219848 0.181322 0.0124252 -0.0414306 0.1792 0.00835136 -0.0411429 0.177956 0.0124252 -0.0407568 0.176286 0.0163769 -0.0596136 0.172647 0.0124252 -0.0685035 0.169317 0.0124252 -0.0771222 0.165569 0.0124252 -0.0940967 0.158034 0.00835136 -0.101103 0.152115 0.0124252 -0.0934433 0.156937 0.0124252 -0.0925666 0.155465 0.0163769 -0.108408 0.146999 0.0124252 -0.114262 0.140292 0.0163769 -0.121905 0.136015 0.0124252 -0.145338 0.112721 0.00835136 -0.144328 0.111938 0.0124252 -0.158325 0.0936073 0.00835136 -0.128084 0.130212 0.0124252 -0.162543 0.0794828 0.0163769 -0.165458 0.0732215 0.0163769 -0.16807 0.0670092 0.0163769 -0.175774 0.0429124 0.0163769 -0.17423 0.0488015 0.0163769 -0.175881 0.0492637 0.0124252 -0.174075 0.0553062 0.0124252 -0.172007 0.0614366 0.0124252 -0.177086 0.0371282 0.0163769 -0.179073 0.0258999 0.0163769 -0.179868 0.0317534 0.0124252 -0.181477 0.0206597 0.0124252 -0.182008 0.0153003 0.0124252 -0.180661 0.00997508 0.0163769 -0.180869 0.00492252 0.0163769 -0.182372 -0.0100696 0.0124252 -0.182008 -0.0153003 0.0124252 -0.17711 -0.0496082 0.00835136 -0.178679 -0.0436218 0.00835136 -0.179454 -0.043811 0.00419604 -0.176053 -0.0559344 0.00419604 -0.175292 -0.0556929 0.00835136 -0.177879 -0.0498233 0.00419604 -0.167025 -0.073915 0.0124252 -0.145338 -0.112721 0.00835136 -0.150682 -0.106855 0.00419604 -0.145968 -0.11321 0.00419604 -0.144328 -0.111938 0.0124252 -0.13388 -0.124245 0.0124252 -0.140268 -0.118971 0.00835136 -0.122758 -0.136966 0.00835136 -0.109166 -0.148027 0.00835136 -0.116655 -0.14323 0.00419604 -0.109639 -0.148669 0.00419604 -0.108408 -0.146999 0.0124252 -0.10181 -0.153179 0.00835136 -0.0940967 -0.158034 0.00835136 -0.0860406 -0.162561 0.00835136 -0.0776615 -0.166727 0.00835136 -0.0600304 -0.173855 0.00835136 -0.0692817 -0.17124 0.00419604 -0.0602908 -0.174609 0.00419604 -0.0596136 -0.172647 0.0124252 -0.0414306 -0.1792 0.00835136 -0.0318521 -0.181148 0.00835136 -0.0221386 -0.18259 0.00835136 -0.0123302 -0.183513 0.00835136 -0.00246871 -0.18391 0.00835136 0.00740345 -0.183778 0.00835136 0.0172437 -0.183117 0.00835136 0.0366607 -0.180236 0.00835136 0.0271269 -0.182722 0.00419604 0.0368197 -0.181018 0.00419604 0.0364061 -0.178985 0.0124252 0.0554613 -0.175366 0.00835136 0.0645388 -0.172232 0.00835136 0.0733579 -0.168664 0.00835136 0.0901103 -0.160341 0.00835136 0.0822452 -0.165405 0.00419604 0.0905012 -0.161036 0.00419604 0.0894846 -0.159228 0.0124252 0.0979974 -0.155646 0.00835136 0.111923 -0.144341 0.0124252 0.105534 -0.150638 0.00835136 0.119502 -0.139815 0.00835136 0.131947 -0.128137 0.00835136 0.126463 -0.134649 0.00419604 0.132519 -0.128693 0.00419604 0.13103 -0.127248 0.0124252 0.141858 -0.115053 0.0124252 0.13759 -0.122057 0.00835136 0.147731 -0.109566 0.00835136 0.151183 -0.102492 0.0124252 0.155299 -0.0961407 0.0124252 0.165593 -0.0770701 0.0124252 0.173075 -0.058361 0.0124252 0.17501 -0.0522733 0.0124252 0.183477 -0.0236878 3.20609e-17 0.182392 -0.0292629 -0.00419604 0.183204 -0.0236526 -0.00419604 0.178129 -0.0403857 0.0124252 0.179342 -0.0346022 0.0124252 0.180343 -0.0289342 0.0124252 0.181146 -0.0233869 0.0124252 0.181764 -0.0179641 0.0124252 0.18221 -0.0126687 0.0124252 0.182496 -0.00750298 0.0124252 0.182633 -0.00246813 0.0124252 0.182633 0.00246813 0.0124252 0.182496 0.00750298 0.0124252 0.18221 0.0126687 0.0124252 0.181764 0.0179641 0.0124252 0.181146 0.0233869 0.0124252 0.180343 0.0289342 0.0124252 0.179342 0.0346022 0.0124252 0.17501 0.0522733 0.0124252 0.172065 0.0649826 0.00835136 0.175041 0.059024 0.00419604 0.172811 0.0652645 0.00419604 0.17087 0.0645314 0.0124252 0.168381 0.0707723 0.0124252 0.162492 0.0834093 0.0124252 0.166751 0.077609 0.00835136 0.155299 0.0961407 0.0124252 0.160178 0.0904003 0.00835136 0.146705 0.108805 0.0124252 0.15224 0.103209 0.00835136 0.14285 0.115857 0.00835136 0.131947 0.128137 0.00835136 0.138187 0.122587 0.00419604 0.132519 0.128693 0.00419604 0.13103 0.127248 0.0124252 0.125917 0.134067 0.00835136 0.111923 0.144341 0.0124252 0.119502 0.139815 0.00835136 0.0979974 0.155646 0.00835136 0.0901103 0.160341 0.00835136 0.0818901 0.164691 0.00835136 0.0645388 0.172232 0.00835136 0.0736761 0.169396 0.00419604 0.0648187 0.172979 0.00419604 0.0640907 0.171036 0.0124252 0.0366607 0.180236 0.00835136 0.0270098 0.181933 0.00835136 0.0172437 0.183117 0.00835136 0.00740345 0.183778 0.00835136 -0.00246871 0.18391 0.00835136 -0.0123302 0.183513 0.00835136 -0.0318521 0.181148 0.00835136 -0.0222346 0.183382 0.00419604 -0.0319903 0.181933 0.00419604 -0.031631 0.17989 0.0124252 -0.0508354 0.176762 0.00835136 -0.0600304 0.173855 0.00835136 -0.0689825 0.170501 0.00835136 -0.0860406 0.162561 0.00835136 -0.0779983 0.16745 0.00419604 -0.0864138 0.163266 0.00419604 -0.0854432 0.161432 0.0124252 -0.10181 0.153179 0.00835136 -0.116151 0.142611 0.00835136 -0.109639 0.148669 0.00419604 -0.116655 0.14323 0.00419604 -0.115345 0.141621 0.0124252 -0.122758 0.136966 0.00835136 -0.139294 0.118144 0.0124252 -0.153286 0.09932 0.0124252 -0.175292 0.0556929 0.00835136 -0.17321 0.0618662 0.00835136 -0.173961 0.0621345 0.00419604 -0.164083 0.0802356 0.0124252 -0.167025 0.073915 0.0124252 -0.169662 0.0676438 0.0124252 -0.180013 0.0377419 0.00835136 -0.181126 0.0319754 0.00835136 -0.177438 0.0433189 0.0124252 -0.178763 0.0374798 0.0124252 -0.180769 0.0261452 0.0124252 -0.182372 0.0100696 0.0124252 -0.182582 0.00496914 0.0124252 -0.182803 0 -0.0120088 -0.182582 -0.00496914 -0.0124252 -0.183733 0 -0.00908643 -0.183647 -0.01014 0.00835136 -0.183859 -0.00500389 -0.00835136 -0.184656 -0.00502559 -0.00419604 -0.184423 0 -0.00609882 -0.183813 -0.0209255 3.1623e-17 -0.183539 -0.0208944 0.00419604 -0.18435 -0.0154972 3.21246e-17 -0.183095 -0.0264816 3.27791e-17 -0.182822 -0.0264422 0.00419604 -0.182183 -0.032162 3.21777e-17 -0.180794 -0.0379056 0.00419604 -0.181912 -0.0321141 0.00419604 -0.17422 -0.0622272 3.4152e-17 -0.173961 -0.0621345 0.00419604 -0.176315 -0.0560178 3.29417e-17 -0.162647 -0.0875728 0.00419604 -0.158325 -0.0936073 0.00835136 -0.159012 -0.0940133 0.00419604 -0.155027 -0.100448 0.00419604 -0.150031 -0.106394 0.00835136 -0.135603 -0.125844 3.36712e-17 -0.135401 -0.125657 0.00419604 -0.141086 -0.119665 3.21333e-17 -0.134817 -0.125114 0.00835136 -0.12954 -0.131692 0.00419604 -0.12329 -0.13756 0.00419604 -0.116151 -0.142611 0.00835136 -0.102252 -0.153843 0.00419604 -0.0945048 -0.15872 0.00419604 -0.0781146 -0.167699 3.45009e-17 -0.0779983 -0.16745 0.00419604 -0.0865426 -0.16351 3.30453e-17 -0.069385 -0.171496 3.29468e-17 -0.0689825 -0.170501 0.00835136 -0.0510558 -0.177529 0.00419604 -0.0416103 -0.179977 0.00419604 -0.0319903 -0.181933 0.00419604 -0.0222346 -0.183382 0.00419604 -0.0123837 -0.184309 0.00419604 -0.00247941 -0.184708 0.00419604 0.0173443 -0.184185 3.41196e-17 0.0173184 -0.183911 0.00419604 0.00744665 -0.18485 3.32932e-17 0.0271674 -0.182994 3.26845e-17 0.0270098 -0.181933 0.00835136 0.0463572 -0.178813 0.00419604 0.0557018 -0.176126 0.00419604 0.0648187 -0.172979 0.00419604 0.0823679 -0.165652 3.28276e-17 0.0737859 -0.169649 3.23504e-17 0.0818901 -0.164691 0.00835136 0.0984225 -0.156321 0.00419604 0.113363 -0.146198 3.18014e-17 0.113194 -0.14598 0.00419604 0.10615 -0.151517 3.31199e-17 0.112705 -0.14535 0.00835136 0.12002 -0.140422 0.00419604 0.125917 -0.134067 0.00835136 0.143684 -0.116533 3.3296e-17 0.14347 -0.11636 0.00419604 0.138393 -0.12277 3.2507e-17 0.14285 -0.115857 0.00835136 0.153128 -0.103811 3.18912e-17 0.1529 -0.103657 0.00419604 0.148593 -0.110205 3.40144e-17 0.15224 -0.103209 0.00835136 0.156385 -0.0968129 0.00835136 0.157064 -0.0972328 0.00419604 0.160872 -0.0907924 0.00419604 0.163629 -0.0839926 0.00835136 0.166751 -0.077609 0.00835136 0.167474 -0.0779456 0.00419604 0.170294 -0.0715763 0.00419604 0.172065 -0.0649826 0.00835136 0.174285 -0.0587691 0.00835136 0.176233 -0.0526388 0.00835136 0.177925 -0.0466021 0.00835136 0.179374 -0.0406681 0.00835136 0.180596 -0.0348441 0.00835136 0.181604 -0.0291365 0.00835136 0.182413 -0.0235504 0.00835136 0.183035 -0.0180897 0.00835136 0.183484 -0.0127573 0.00835136 0.183772 -0.00755545 0.00835136 0.18391 -0.00248538 0.00835136 0.18391 0.00248538 0.00835136 0.183772 0.00755545 0.00835136 0.183484 0.0127573 0.00835136 0.183035 0.0180897 0.00835136 0.182413 0.0235504 0.00835136 0.181604 0.0291365 0.00835136 0.180596 0.0348441 0.00835136 0.178963 0.046874 3.43272e-17 0.178697 0.0468043 0.00419604 0.180421 0.0409053 3.40536e-17 0.177925 0.0466021 0.00835136 0.176233 0.0526388 0.00835136 0.174285 0.0587691 0.00835136 0.169558 0.0712672 0.00835136 0.164583 0.0844826 3.35775e-17 0.164338 0.0843569 0.00419604 0.167724 0.0780619 3.24124e-17 0.163629 0.0839926 0.00835136 0.157298 0.0973778 3.32567e-17 0.157064 0.0972328 0.00419604 0.161112 0.0909278 3.22486e-17 0.156385 0.0968129 0.00835136 0.148593 0.110205 3.33944e-17 0.148372 0.110041 0.00419604 0.153128 0.103811 3.33644e-17 0.147731 0.109566 0.00835136 0.14347 0.11636 0.00419604 0.13759 0.122057 0.00835136 0.126463 0.134649 0.00419604 0.113363 0.146198 3.32921e-17 0.113194 0.14598 0.00419604 0.120199 0.140631 3.35142e-17 0.112705 0.14535 0.00835136 0.105991 0.151291 0.00419604 0.0984225 0.156321 0.00419604 0.0905012 0.161036 0.00419604 0.0737859 0.169649 3.34146e-17 0.0823679 0.165652 3.38798e-17 0.0733579 0.168664 0.00835136 0.0557018 0.176126 0.00419604 0.0463572 0.178813 0.00419604 0.0368197 0.181018 0.00419604 0.0271269 0.182722 0.00419604 0.0173184 0.183911 0.00419604 0.00743556 0.184575 0.00419604 -0.00247941 0.184708 0.00419604 -0.0222677 0.183655 3.31856e-17 -0.0124021 0.184584 3.37128e-17 -0.0221386 0.18259 0.00835136 -0.0416103 0.179977 0.00419604 -0.0510558 0.177529 0.00419604 -0.0602908 0.174609 0.00419604 -0.0692817 0.17124 0.00419604 -0.0776615 0.166727 0.00835136 -0.0945048 0.15872 0.00419604 -0.102252 0.153843 0.00419604 -0.109166 0.148027 0.00835136 -0.12329 0.13756 0.00419604 -0.135401 0.125657 0.00419604 -0.140268 0.118971 0.00835136 -0.140876 0.119487 0.00419604 -0.145968 0.11321 0.00419604 -0.150031 0.106394 0.00835136 -0.161945 0.0871946 0.00835136 -0.16523 0.0807966 0.00835136 -0.168193 0.0744319 0.00835136 -0.170848 0.0681168 0.00835136 -0.17711 0.0496082 0.00835136 -0.178679 0.0436218 0.00835136 -0.176053 0.0559344 0.00419604 -0.182033 0.026328 0.00835136 -0.182746 0.0208042 0.00835136 -0.181912 0.0321141 0.00419604 -0.18328 0.0154073 0.00835136 -0.183539 0.0208944 0.00419604 -0.184075 0.0154741 0.00419604 -0.183859 0.00500389 0.00835136 -0.183647 0.01014 0.00835136 -0.184444 -0.010184 0.00419604 -0.184075 -0.0154741 0.00419604 -0.179722 -0.0438763 3.25871e-17 -0.181063 -0.0379621 3.35326e-17 -0.180794 -0.0379056 -0.00419604 -0.178144 -0.0498976 3.2603e-17 -0.179454 -0.043811 -0.00419604 -0.173961 -0.0621345 -0.00419604 -0.166194 -0.0812681 3.33168e-17 -0.16289 -0.0877033 3.27923e-17 -0.159249 -0.0941535 3.30863e-17 -0.155258 -0.100598 3.31003e-17 -0.150907 -0.107015 3.21135e-17 -0.146186 -0.113379 3.21866e-17 -0.140876 -0.119487 0.00419604 -0.129733 -0.131888 3.31848e-17 -0.116655 -0.14323 -0.00419604 -0.116829 -0.143443 3.34094e-17 -0.12329 -0.13756 -0.00419604 -0.109803 -0.14889 3.37631e-17 -0.102404 -0.154072 3.26592e-17 -0.0864138 -0.163266 -0.00419604 -0.0945048 -0.15872 -0.00419604 -0.0864138 -0.163266 0.00419604 -0.0603807 -0.174869 3.21788e-17 -0.051132 -0.177793 3.30934e-17 -0.0416723 -0.180245 3.28787e-17 -0.032038 -0.182205 3.30551e-17 -0.0222677 -0.183655 3.31856e-17 -0.00247941 -0.184708 -0.00419604 -0.00248311 -0.184983 3.37493e-17 -0.0123837 -0.184309 -0.00419604 0.00743556 -0.184575 -0.00419604 0.00743556 -0.184575 0.00419604 0.0368746 -0.181288 3.34122e-17 0.0464263 -0.17908 3.32108e-17 0.0557849 -0.176389 3.42666e-17 0.0736761 -0.169396 -0.00419604 0.0648187 -0.172979 -0.00419604 0.0736761 -0.169396 0.00419604 0.0906361 -0.161276 3.32492e-17 0.0985692 -0.156554 3.27958e-17 0.105991 -0.151291 0.00419604 0.120199 -0.140631 3.20485e-17 0.126652 -0.134849 3.30151e-17 0.132716 -0.128885 3.31529e-17 0.138187 -0.122587 0.00419604 0.148372 -0.110041 0.00419604 0.164338 -0.0843569 -0.00419604 0.164583 -0.0844826 3.23444e-17 0.160872 -0.0907924 -0.00419604 0.164338 -0.0843569 0.00419604 0.172811 -0.0652645 -0.00419604 0.173069 -0.0653618 3.36554e-17 0.170294 -0.0715763 -0.00419604 0.172811 -0.0652645 0.00419604 0.175041 -0.059024 0.00419604 0.176998 -0.0528671 0.00419604 0.178697 -0.0468043 0.00419604 0.180152 -0.0408444 0.00419604 0.181379 -0.0349952 0.00419604 0.182392 -0.0292629 0.00419604 0.183204 -0.0236526 0.00419604 0.183829 -0.0181681 0.00419604 0.18428 -0.0128126 0.00419604 0.184569 -0.00758822 0.00419604 0.184708 -0.00249616 0.00419604 0.184708 0.00249616 0.00419604 0.184569 0.00758822 0.00419604 0.18428 0.0128126 0.00419604 0.183829 0.0181681 0.00419604 0.183204 0.0236526 0.00419604 0.182392 0.0292629 0.00419604 0.181379 0.0349952 0.00419604 0.180152 0.0408444 0.00419604 0.176998 0.0528671 0.00419604 0.175302 0.059112 3.36713e-17 0.173069 0.0653618 3.23219e-17 0.170294 0.0715763 0.00419604 0.167474 0.0779456 0.00419604 0.160872 0.0907924 0.00419604 0.1529 0.103657 0.00419604 0.143684 0.116533 3.32055e-17 0.138393 0.12277 3.35228e-17 0.132716 0.128885 3.27762e-17 0.126652 0.134849 3.28231e-17 0.12002 0.140422 0.00419604 0.10615 0.151517 3.2615e-17 0.0985692 0.156554 3.33082e-17 0.0822452 0.165405 -0.00419604 0.0905012 0.161036 -0.00419604 0.0822452 0.165405 0.00419604 0.0649154 0.173237 3.24628e-17 0.0557849 0.176389 3.3399e-17 0.0464263 0.17908 3.34292e-17 0.0368746 0.181288 3.34122e-17 0.0271674 0.182994 3.40095e-17 0.0173443 0.184185 3.32333e-17 -0.00247941 0.184708 -0.00419604 -0.00248311 0.184983 3.37493e-17 0.00743556 0.184575 -0.00419604 -0.0123837 0.184309 -0.00419604 -0.0123837 0.184309 0.00419604 -0.032038 0.182205 3.30551e-17 -0.0416723 0.180245 3.33171e-17 -0.051132 0.177793 3.30934e-17 -0.0603807 0.174869 3.19628e-17 -0.0779983 0.16745 -0.00419604 -0.0781146 0.167699 3.30193e-17 -0.0692817 0.17124 -0.00419604 -0.0865426 0.16351 3.17905e-17 -0.0946458 0.158957 3.30265e-17 -0.109639 0.148669 -0.00419604 -0.109803 0.14889 3.20599e-17 -0.102252 0.153843 -0.00419604 -0.116829 0.143443 3.15369e-17 -0.12954 0.131692 -0.00419604 -0.129733 0.131888 3.34701e-17 -0.12329 0.13756 -0.00419604 -0.135603 0.125844 3.28317e-17 -0.141086 0.119665 3.21791e-17 -0.146186 0.113379 3.43802e-17 -0.158325 0.0936073 -0.00835136 -0.161945 0.0871946 -0.00835136 -0.165947 0.0811471 0.00419604 -0.168923 0.0747547 0.00419604 -0.171589 0.0684123 0.00419604 -0.180794 0.0379056 0.00419604 -0.179454 0.043811 0.00419604 -0.179722 0.0438763 3.29648e-17 -0.177879 0.0498233 0.00419604 -0.176315 0.0560178 3.47135e-17 -0.17422 0.0622272 3.44209e-17 -0.182822 0.0264422 0.00419604 -0.182183 0.032162 3.44054e-17 -0.183813 0.0209255 3.16365e-17 -0.18435 0.0154972 3.27277e-17 -0.184656 0.00502559 0.00419604 -0.184444 0.010184 0.00419604 -0.184853 0 -0.00306226 -0.184719 -0.0101991 3.27083e-17 -0.180869 -0.00492252 -0.0163769 -0.181654 0 -0.014852 -0.182746 -0.0208042 -0.00835136 -0.182008 -0.0153003 -0.0124252 -0.181477 -0.0206597 -0.0124252 -0.180769 -0.0261452 -0.0124252 -0.182033 -0.026328 -0.00835136 -0.174075 -0.0553062 -0.0124252 -0.175292 -0.0556929 -0.00835136 -0.175881 -0.0492637 -0.0124252 -0.159012 -0.0940133 -0.00419604 -0.161945 -0.0871946 -0.00835136 -0.158325 -0.0936073 -0.00835136 -0.150682 -0.106855 -0.00419604 -0.154357 -0.100014 -0.00835136 -0.150031 -0.106394 -0.00835136 -0.145968 -0.11321 -0.00419604 -0.140876 -0.119487 -0.00419604 -0.135401 -0.125657 -0.00419604 -0.12954 -0.131692 -0.00419604 -0.123474 -0.137765 3.23476e-17 -0.109639 -0.148669 -0.00419604 -0.102252 -0.153843 -0.00419604 -0.0946458 -0.158957 3.37489e-17 -0.0779983 -0.16745 -0.00419604 -0.0692817 -0.17124 -0.00419604 -0.0602908 -0.174609 -0.00419604 -0.0510558 -0.177529 -0.00419604 -0.0416103 -0.179977 -0.00419604 -0.0222346 -0.183382 -0.00419604 -0.0318521 -0.181148 -0.00835136 -0.0221386 -0.18259 -0.00835136 -0.0123302 -0.183513 -0.00835136 -0.0124021 -0.184584 3.32692e-17 0.0173184 -0.183911 -0.00419604 0.0271269 -0.182722 -0.00419604 0.0368197 -0.181018 -0.00419604 0.0463572 -0.178813 -0.00419604 0.0554613 -0.175366 -0.00835136 0.0645388 -0.172232 -0.00835136 0.0649154 -0.173237 3.26778e-17 0.0822452 -0.165405 -0.00419604 0.0905012 -0.161036 -0.00419604 0.105991 -0.151291 -0.00419604 0.0979974 -0.155646 -0.00835136 0.105534 -0.150638 -0.00835136 0.113194 -0.14598 -0.00419604 0.126463 -0.134649 -0.00419604 0.119502 -0.139815 -0.00835136 0.125917 -0.134067 -0.00835136 0.132519 -0.128693 -0.00419604 0.138187 -0.122587 -0.00419604 0.14347 -0.11636 -0.00419604 0.148372 -0.110041 -0.00419604 0.1529 -0.103657 -0.00419604 0.157298 -0.0973778 3.38921e-17 0.161112 -0.0909278 3.3118e-17 0.167724 -0.0780619 3.28367e-17 0.170548 -0.071683 3.32728e-17 0.175302 -0.059112 3.39872e-17 0.177262 -0.0529459 3.19864e-17 0.178963 -0.046874 3.45098e-17 0.180421 -0.0409053 3.25369e-17 0.18165 -0.0350474 3.38061e-17 0.182664 -0.0293065 3.49819e-17 0.184103 -0.0181952 3.51192e-17 0.184554 -0.0128318 3.41922e-17 0.184844 -0.00759953 3.32879e-17 0.184983 -0.00249989 3.42068e-17 0.184983 0.00249989 3.44193e-17 0.183035 0.0180897 -0.00835136 0.183829 0.0181681 -0.00419604 0.183484 0.0127573 -0.00835136 0.184844 0.00759953 3.39654e-17 0.184554 0.0128318 3.15612e-17 0.184103 0.0181952 3.28823e-17 0.183477 0.0236878 3.22028e-17 0.182664 0.0293065 3.3526e-17 0.18165 0.0350474 3.38329e-17 0.180152 0.0408444 -0.00419604 0.178697 0.0468043 -0.00419604 0.177262 0.0529459 3.22496e-17 0.170294 0.0715763 -0.00419604 0.172065 0.0649826 -0.00835136 0.169558 0.0712672 -0.00835136 0.170548 0.071683 3.36868e-17 0.167474 0.0779456 -0.00419604 0.164338 0.0843569 -0.00419604 0.160872 0.0907924 -0.00419604 0.157064 0.0972328 -0.00419604 0.1529 0.103657 -0.00419604 0.148372 0.110041 -0.00419604 0.138187 0.122587 -0.00419604 0.14285 0.115857 -0.00835136 0.13759 0.122057 -0.00835136 0.132519 0.128693 -0.00419604 0.12002 0.140422 -0.00419604 0.125917 0.134067 -0.00835136 0.119502 0.139815 -0.00835136 0.113194 0.14598 -0.00419604 0.105991 0.151291 -0.00419604 0.0979974 0.155646 -0.00835136 0.0901103 0.160341 -0.00835136 0.0906361 0.161276 3.40805e-17 0.0736761 0.169396 -0.00419604 0.0648187 0.172979 -0.00419604 0.0557018 0.176126 -0.00419604 0.0463572 0.178813 -0.00419604 0.0368197 0.181018 -0.00419604 0.0173184 0.183911 -0.00419604 0.0270098 0.181933 -0.00835136 0.0172437 0.183117 -0.00835136 0.00740345 0.183778 -0.00835136 0.00744665 0.18485 3.24054e-17 -0.0222346 0.183382 -0.00419604 -0.0319903 0.181933 -0.00419604 -0.0416103 0.179977 -0.00419604 -0.0510558 0.177529 -0.00419604 -0.0600304 0.173855 -0.00835136 -0.0689825 0.170501 -0.00835136 -0.069385 0.171496 3.33747e-17 -0.0864138 0.163266 -0.00419604 -0.0945048 0.15872 -0.00419604 -0.102404 0.154072 3.41854e-17 -0.116655 0.14323 -0.00419604 -0.123474 0.137765 3.3316e-17 -0.140876 0.119487 -0.00419604 -0.134817 0.125114 -0.00835136 -0.140268 0.118971 -0.00835136 -0.150682 0.106855 -0.00419604 -0.145338 0.112721 -0.00835136 -0.150031 0.106394 -0.00835136 -0.150907 0.107015 3.36468e-17 -0.171845 0.0685143 3.40792e-17 -0.168923 0.0747547 -0.00419604 -0.171589 0.0684123 -0.00419604 -0.166194 0.0812681 3.32369e-17 -0.169175 0.0748662 3.36854e-17 -0.178144 0.0498976 3.38321e-17 -0.173961 0.0621345 -0.00419604 -0.176053 0.0559344 -0.00419604 -0.181063 0.0379621 3.31834e-17 -0.181912 0.0321141 -0.00419604 -0.181126 0.0319754 -0.00835136 -0.182822 0.0264422 -0.00419604 -0.183095 0.0264816 3.24901e-17 -0.183539 0.0208944 -0.00419604 -0.184075 0.0154741 -0.00419604 -0.184932 0.00503308 3.28443e-17 -0.184719 0.0101991 3.18629e-17 -0.177063 0 -0.022809 -0.178762 -0.00486518 -0.0201657 -0.17877 0 -0.0202607 -0.184444 -0.010184 -0.00419604 -0.184075 -0.0154741 -0.00419604 -0.183539 -0.0208944 -0.00419604 -0.182822 -0.0264422 -0.00419604 -0.181912 -0.0321141 -0.00419604 -0.179868 -0.0317534 -0.0124252 -0.180013 -0.0377419 -0.00835136 -0.181126 -0.0319754 -0.00835136 -0.177086 -0.0371282 -0.0163769 -0.177438 -0.0433189 -0.0124252 -0.178763 -0.0374798 -0.0124252 -0.177879 -0.0498233 -0.00419604 -0.176053 -0.0559344 -0.00419604 -0.165947 -0.0811471 -0.00419604 -0.162647 -0.0875728 -0.00419604 -0.155027 -0.100448 -0.00419604 -0.140268 -0.118971 -0.00835136 -0.144328 -0.111938 -0.0124252 -0.139294 -0.118144 -0.0124252 -0.134817 -0.125114 -0.00835136 -0.122758 -0.136966 -0.00835136 -0.128084 -0.130212 -0.0124252 -0.121905 -0.136015 -0.0124252 -0.116151 -0.142611 -0.00835136 -0.109166 -0.148027 -0.00835136 -0.0940967 -0.158034 -0.00835136 -0.101103 -0.152115 -0.0124252 -0.0934433 -0.156937 -0.0124252 -0.0860406 -0.162561 -0.00835136 -0.0776615 -0.166727 -0.00835136 -0.0689825 -0.170501 -0.00835136 -0.0600304 -0.173855 -0.00835136 -0.0414306 -0.1792 -0.00835136 -0.0504824 -0.175535 -0.0124252 -0.0411429 -0.177956 -0.0124252 -0.031631 -0.17989 -0.0124252 -0.0319903 -0.181933 -0.00419604 -0.00246871 -0.18391 -0.00835136 0.00740345 -0.183778 -0.00835136 0.0172437 -0.183117 -0.00835136 0.0270098 -0.181933 -0.00835136 0.0366607 -0.180236 -0.00835136 0.0458365 -0.176805 -0.0124252 0.0550761 -0.174148 -0.0124252 0.0557018 -0.176126 -0.00419604 0.0733579 -0.168664 -0.00835136 0.0818901 -0.164691 -0.00835136 0.0901103 -0.160341 -0.00835136 0.0984225 -0.156321 -0.00419604 0.112705 -0.14535 -0.00835136 0.12002 -0.140422 -0.00419604 0.13759 -0.122057 -0.00835136 0.13103 -0.127248 -0.0124252 0.136635 -0.12121 -0.0124252 0.14285 -0.115857 -0.00835136 0.155299 -0.0961407 -0.0124252 0.156385 -0.0968129 -0.00835136 0.151183 -0.102492 -0.0124252 0.157064 -0.0972328 -0.00419604 0.160178 -0.0904003 -0.00835136 0.163629 -0.0839926 -0.00835136 0.167474 -0.0779456 -0.00419604 0.173075 -0.058361 -0.0124252 0.174285 -0.0587691 -0.00835136 0.17087 -0.0645314 -0.0124252 0.175041 -0.059024 -0.00419604 0.176998 -0.0528671 -0.00419604 0.178697 -0.0468043 -0.00419604 0.180152 -0.0408444 -0.00419604 0.181379 -0.0349952 -0.00419604 0.183829 -0.0181681 -0.00419604 0.18428 -0.0128126 -0.00419604 0.184569 -0.00758822 -0.00419604 0.184708 -0.00249616 -0.00419604 0.184708 0.00249616 -0.00419604 0.184569 0.00758822 -0.00419604 0.18428 0.0128126 -0.00419604 0.183204 0.0236526 -0.00419604 0.182392 0.0292629 -0.00419604 0.181379 0.0349952 -0.00419604 0.17501 0.0522733 -0.0124252 0.176233 0.0526388 -0.00835136 0.17669 0.0462785 -0.0124252 0.176998 0.0528671 -0.00419604 0.175041 0.059024 -0.00419604 0.172811 0.0652645 -0.00419604 0.166751 0.077609 -0.00835136 0.163629 0.0839926 -0.00835136 0.160178 0.0904003 -0.00835136 0.156385 0.0968129 -0.00835136 0.15224 0.103209 -0.00835136 0.147731 0.109566 -0.00835136 0.14347 0.11636 -0.00419604 0.131947 0.128137 -0.00835136 0.126463 0.134649 -0.00419604 0.112705 0.14535 -0.00835136 0.104801 0.149592 -0.0124252 0.097317 0.154565 -0.0124252 0.0984225 0.156321 -0.00419604 0.0818901 0.164691 -0.00835136 0.0733579 0.168664 -0.00835136 0.0645388 0.172232 -0.00835136 0.0554613 0.175366 -0.00835136 0.0366607 0.180236 -0.00835136 0.0458365 0.176805 -0.0124252 0.0364061 0.178985 -0.0124252 0.0268222 0.18067 -0.0124252 0.0271269 0.182722 -0.00419604 -0.00246871 0.18391 -0.00835136 -0.0123302 0.183513 -0.00835136 -0.0221386 0.18259 -0.00835136 -0.0318521 0.181148 -0.00835136 -0.0414306 0.1792 -0.00835136 -0.0504824 0.175535 -0.0124252 -0.0596136 0.172647 -0.0124252 -0.0602908 0.174609 -0.00419604 -0.0776615 0.166727 -0.00835136 -0.0860406 0.162561 -0.00835136 -0.10181 0.153179 -0.00835136 -0.0934433 0.156937 -0.0124252 -0.101103 0.152115 -0.0124252 -0.109166 0.148027 -0.00835136 -0.122758 0.136966 -0.00835136 -0.115345 0.141621 -0.0124252 -0.121905 0.136015 -0.0124252 -0.12898 0.131123 -0.00835136 -0.135401 0.125657 -0.00419604 -0.145968 0.11321 -0.00419604 -0.154357 0.100014 -0.00835136 -0.165947 0.0811471 -0.00419604 -0.179454 0.043811 -0.00419604 -0.177879 0.0498233 -0.00419604 -0.17711 0.0496082 -0.00835136 -0.175292 0.0556929 -0.00835136 -0.17321 0.0618662 -0.00835136 -0.180794 0.0379056 -0.00419604 -0.182746 0.0208042 -0.00835136 -0.18328 0.0154073 -0.00835136 -0.184444 0.010184 -0.00419604 -0.184656 0.00502559 -0.00419604 -0.183647 -0.01014 -0.00835136 -0.18328 -0.0154073 -0.00835136 -0.178679 -0.0436218 -0.00835136 -0.17711 -0.0496082 -0.00835136 -0.168193 -0.0744319 -0.00835136 -0.16082 -0.0865891 -0.0124252 -0.157225 -0.0929573 -0.0124252 -0.153286 -0.09932 -0.0124252 -0.14899 -0.105655 -0.0124252 -0.145338 -0.112721 -0.00835136 -0.13388 -0.124245 -0.0124252 -0.12898 -0.131123 -0.00835136 -0.115345 -0.141621 -0.0124252 -0.107391 -0.14562 -0.0163769 -0.100155 -0.150688 -0.0163769 -0.10181 -0.153179 -0.00835136 -0.0854432 -0.161432 -0.0124252 -0.0771222 -0.165569 -0.0124252 -0.0685035 -0.169317 -0.0124252 -0.0590543 -0.171027 -0.0163769 -0.0500087 -0.173888 -0.0163769 -0.0508354 -0.176762 -0.00835136 -0.0219848 -0.181322 -0.0124252 -0.0122446 -0.182239 -0.0124252 -0.00245156 -0.182633 -0.0124252 0.00735204 -0.182502 -0.0124252 0.0171239 -0.181845 -0.0124252 0.0268222 -0.18067 -0.0124252 0.0360646 -0.177305 -0.0163769 0.0454064 -0.175146 -0.0163769 0.046157 -0.178041 -0.00835136 0.0640907 -0.171036 -0.0124252 0.0728485 -0.167493 -0.0124252 0.0813214 -0.163547 -0.0124252 0.097317 -0.154565 -0.0124252 0.088645 -0.157734 -0.0163769 0.0964039 -0.153115 -0.0163769 0.104801 -0.149592 -0.0124252 0.117559 -0.137542 -0.0163769 0.118672 -0.138844 -0.0124252 0.110873 -0.142986 -0.0163769 0.125043 -0.133136 -0.0124252 0.131947 -0.128137 -0.00835136 0.145329 -0.107784 -0.0163769 0.146705 -0.108805 -0.0124252 0.140527 -0.113973 -0.0163769 0.147731 -0.109566 -0.00835136 0.15224 -0.103209 -0.00835136 0.164039 -0.076347 -0.0163769 0.165593 -0.0770701 -0.0124252 0.160968 -0.0826267 -0.0163769 0.166751 -0.077609 -0.00835136 0.169558 -0.0712672 -0.00835136 0.172065 -0.0649826 -0.00835136 0.176233 -0.0526388 -0.00835136 0.177925 -0.0466021 -0.00835136 0.179374 -0.0406681 -0.00835136 0.180596 -0.0348441 -0.00835136 0.181604 -0.0291365 -0.00835136 0.182413 -0.0235504 -0.00835136 0.183035 -0.0180897 -0.00835136 0.183484 -0.0127573 -0.00835136 0.183772 -0.00755545 -0.00835136 0.18391 -0.00248538 -0.00835136 0.18391 0.00248538 -0.00835136 0.183772 0.00755545 -0.00835136 0.182413 0.0235504 -0.00835136 0.181764 0.0179641 -0.0124252 0.181146 0.0233869 -0.0124252 0.181604 0.0291365 -0.00835136 0.180596 0.0348441 -0.00835136 0.179374 0.0406681 -0.00835136 0.177925 0.0466021 -0.00835136 0.174285 0.0587691 -0.00835136 0.17087 0.0645314 -0.0124252 0.168381 0.0707723 -0.0124252 0.157573 0.0889303 -0.0163769 0.159065 0.0897726 -0.0124252 0.160968 0.0826267 -0.0163769 0.149764 0.101531 -0.0163769 0.151183 0.102492 -0.0124252 0.153842 0.0952386 -0.0163769 0.140527 0.113973 -0.0163769 0.141858 0.115053 -0.0124252 0.145329 0.107784 -0.0163769 0.136635 0.12121 -0.0124252 0.125043 0.133136 -0.0124252 0.129801 0.126054 -0.0163769 0.123869 0.131887 -0.0163769 0.118672 0.138844 -0.0124252 0.111923 0.144341 -0.0124252 0.105534 0.150638 -0.00835136 0.0894846 0.159228 -0.0124252 0.0813214 0.163547 -0.0124252 0.0728485 0.167493 -0.0124252 0.0550761 0.174148 -0.0124252 0.0634893 0.169431 -0.0163769 0.0545594 0.172514 -0.0163769 0.0454064 0.175146 -0.0163769 0.046157 0.178041 -0.00835136 0.0171239 0.181845 -0.0124252 0.00735204 0.182502 -0.0124252 -0.00245156 0.182633 -0.0124252 -0.0122446 0.182239 -0.0124252 -0.0219848 0.181322 -0.0124252 -0.031631 0.17989 -0.0124252 -0.0407568 0.176286 -0.0163769 -0.0500087 0.173888 -0.0163769 -0.0508354 0.176762 -0.00835136 -0.0685035 0.169317 -0.0124252 -0.0771222 0.165569 -0.0124252 -0.0925666 0.155465 -0.0163769 -0.0846415 0.159918 -0.0163769 -0.0940967 0.158034 -0.00835136 -0.108408 0.146999 -0.0124252 -0.116151 0.142611 -0.00835136 -0.128084 0.130212 -0.0124252 -0.13388 0.124245 -0.0124252 -0.139294 0.118144 -0.0124252 -0.144328 0.111938 -0.0124252 -0.14899 0.105655 -0.0124252 -0.15575 0.0920851 -0.0163769 -0.168193 0.0744319 -0.00835136 -0.170848 0.0681168 -0.00835136 -0.157225 0.0929573 -0.0124252 -0.178763 0.0374798 -0.0124252 -0.179868 0.0317534 -0.0124252 -0.178679 0.0436218 -0.00835136 -0.172007 0.0614366 -0.0124252 -0.174075 0.0553062 -0.0124252 -0.180013 0.0377419 -0.00835136 -0.182033 0.026328 -0.00835136 -0.181477 0.0206597 -0.0124252 -0.182008 0.0153003 -0.0124252 -0.183859 0.00500389 -0.00835136 -0.183647 0.01014 -0.00835136 -0.17102 0 -0.0297296 -0.17354 -0.00472304 -0.0270916 -0.17318 0 -0.0275526 -0.182372 -0.0100696 -0.0124252 -0.176305 -0.0047983 -0.0237508 -0.175197 0 -0.0252426 -0.177681 -0.0202275 -0.0201657 -0.179775 -0.0204659 -0.0163769 -0.1782 -0.0149802 -0.0201657 -0.176987 -0.0255982 -0.0201657 -0.179073 -0.0258999 -0.0163769 -0.17423 -0.0488015 -0.0163769 -0.175774 -0.0429124 -0.0163769 -0.173726 -0.0424126 -0.0201657 -0.165458 -0.0732215 -0.0163769 -0.162543 -0.0794828 -0.0163769 -0.150079 -0.0972421 -0.0201657 -0.151847 -0.0983881 -0.0163769 -0.153936 -0.0910126 -0.0201657 -0.147592 -0.104664 -0.0163769 -0.142974 -0.110888 -0.0163769 -0.137987 -0.117036 -0.0163769 -0.125405 -0.127488 -0.0201657 -0.126883 -0.128991 -0.0163769 -0.13108 -0.121646 -0.0201657 -0.120761 -0.134739 -0.0163769 -0.112932 -0.138658 -0.0201657 -0.10614 -0.143923 -0.0201657 -0.108408 -0.146999 -0.0124252 -0.0925666 -0.155465 -0.0163769 -0.0846415 -0.159918 -0.0163769 -0.0763986 -0.164015 -0.0163769 -0.0583664 -0.169035 -0.0201657 -0.0670704 -0.165775 -0.0201657 -0.0596136 -0.172647 -0.0124252 -0.0407568 -0.176286 -0.0163769 -0.0313342 -0.178202 -0.0163769 -0.0217786 -0.17962 -0.0163769 -0.0121297 -0.180529 -0.0163769 -0.00242856 -0.18092 -0.0163769 0.00728306 -0.180789 -0.0163769 0.0169633 -0.180139 -0.0163769 0.0262611 -0.17689 -0.0201657 0.0356445 -0.17524 -0.0201657 0.0364061 -0.178985 -0.0124252 0.0545594 -0.172514 -0.0163769 0.0634893 -0.169431 -0.0163769 0.072165 -0.165922 -0.0163769 0.0876125 -0.155896 -0.0201657 0.0796201 -0.160126 -0.0201657 0.0894846 -0.159228 -0.0124252 0.103818 -0.148188 -0.0163769 0.111923 -0.144341 -0.0124252 0.123869 -0.131887 -0.0163769 0.129801 -0.126054 -0.0163769 0.135353 -0.120073 -0.0163769 0.141858 -0.115053 -0.0124252 0.149764 -0.101531 -0.0163769 0.153842 -0.0952386 -0.0163769 0.159065 -0.0897726 -0.0124252 0.162492 -0.0834093 -0.0124252 0.168381 -0.0707723 -0.0124252 0.171348 -0.0511797 -0.0201657 0.173368 -0.0517828 -0.0163769 0.169454 -0.0571401 -0.0201657 0.17501 -0.0522733 -0.0124252 0.17669 -0.0462785 -0.0124252 0.178129 -0.0403857 -0.0124252 0.179342 -0.0346022 -0.0124252 0.180343 -0.0289342 -0.0124252 0.181146 -0.0233869 -0.0124252 0.181764 -0.0179641 -0.0124252 0.18221 -0.0126687 -0.0124252 0.182496 -0.00750298 -0.0124252 0.182633 -0.00246813 -0.0124252 0.182633 0.00246813 -0.0124252 0.182496 0.00750298 -0.0124252 0.18221 0.0126687 -0.0124252 0.17559 0.0338783 -0.0201657 0.174143 0.0279395 -0.0237508 0.173176 0.0334125 -0.0237508 0.180343 0.0289342 -0.0124252 0.179342 0.0346022 -0.0124252 0.178129 0.0403857 -0.0124252 0.169454 0.0571401 -0.0201657 0.171451 0.0578135 -0.0163769 0.171348 0.0511797 -0.0201657 0.173075 0.058361 -0.0124252 0.162129 0.0754578 -0.0201657 0.164039 0.076347 -0.0163769 0.164858 0.0692917 -0.0201657 0.165593 0.0770701 -0.0124252 0.162492 0.0834093 -0.0124252 0.155299 0.0961407 -0.0124252 0.146705 0.108805 -0.0124252 0.135353 0.120073 -0.0163769 0.13103 0.127248 -0.0124252 0.117559 0.137542 -0.0163769 0.102608 0.146462 -0.0201657 0.103818 0.148188 -0.0163769 0.109581 0.141321 -0.0201657 0.0964039 0.153115 -0.0163769 0.088645 0.157734 -0.0163769 0.0805584 0.162013 -0.0163769 0.0713245 0.163989 -0.0201657 0.0627498 0.167458 -0.0201657 0.0640907 0.171036 -0.0124252 0.0360646 0.177305 -0.0163769 0.0265706 0.178974 -0.0163769 0.0169633 0.180139 -0.0163769 0.00728306 0.180789 -0.0163769 -0.00242856 0.18092 -0.0163769 -0.0121297 0.180529 -0.0163769 -0.0215249 0.177528 -0.0201657 -0.0309692 0.176126 -0.0201657 -0.0313342 0.178202 -0.0163769 -0.0402821 0.174233 -0.0201657 -0.0411429 0.177956 -0.0124252 -0.0590543 0.171027 -0.0163769 -0.0678608 0.167728 -0.0163769 -0.0763986 0.164015 -0.0163769 -0.0854432 0.161432 -0.0124252 -0.100155 0.150688 -0.0163769 -0.112932 0.138658 -0.0201657 -0.114262 0.140292 -0.0163769 -0.10614 0.143923 -0.0201657 -0.120761 0.134739 -0.0163769 -0.13108 0.121646 -0.0201657 -0.132624 0.12308 -0.0163769 -0.125405 0.127488 -0.0201657 -0.141309 0.109597 -0.0201657 -0.142974 0.110888 -0.0163769 -0.13638 0.115673 -0.0201657 -0.150079 0.0972421 -0.0201657 -0.151847 0.0983881 -0.0163769 -0.145873 0.103445 -0.0201657 -0.153286 0.09932 -0.0124252 -0.169662 0.0676438 -0.0124252 -0.175881 0.0492637 -0.0124252 -0.177438 0.0433189 -0.0124252 -0.172442 0.0547872 -0.0163769 -0.170393 0.0608602 -0.0163769 -0.180769 0.0261452 -0.0124252 -0.178181 0.0314555 -0.0163769 -0.179775 0.0204659 -0.0163769 -0.1803 0.0151568 -0.0163769 -0.182582 0.00496914 -0.0124252 -0.182372 0.0100696 -0.0124252 -0.180304 0 -0.0176057 -0.180661 -0.00997508 -0.0163769 -0.1803 -0.0151568 -0.0163769 -0.178181 -0.0314555 -0.0163769 -0.173685 -0.0306617 -0.0237508 -0.175023 -0.0366957 -0.0201657 -0.176105 -0.0310891 -0.0201657 -0.169834 -0.04757 -0.0237508 -0.155291 -0.0836122 -0.0237508 -0.157456 -0.0847776 -0.0201657 -0.158442 -0.0774771 -0.0237508 -0.159312 -0.0857767 -0.0163769 -0.15575 -0.0920851 -0.0163769 -0.139366 -0.10809 -0.0237508 -0.141309 -0.109597 -0.0201657 -0.143867 -0.102023 -0.0237508 -0.13638 -0.115673 -0.0201657 -0.132624 -0.12308 -0.0163769 -0.119355 -0.133169 -0.0201657 -0.114262 -0.140292 -0.0163769 -0.0989883 -0.148933 -0.0201657 -0.0914884 -0.153654 -0.0201657 -0.0836556 -0.158055 -0.0201657 -0.0744708 -0.159877 -0.0237508 -0.0661484 -0.163496 -0.0237508 -0.0678608 -0.167728 -0.0163769 -0.0494262 -0.171862 -0.0201657 -0.0402821 -0.174233 -0.0201657 -0.0309692 -0.176126 -0.0201657 -0.0215249 -0.177528 -0.0201657 -0.0119884 -0.178426 -0.0201657 -0.00240027 -0.178812 -0.0201657 0.00709928 -0.176227 -0.0237508 0.0165352 -0.175593 -0.0237508 0.0167657 -0.178041 -0.0201657 0.0259001 -0.174458 -0.0237508 0.0265706 -0.178974 -0.0163769 0.0448775 -0.173106 -0.0201657 0.0539239 -0.170505 -0.0201657 0.0627498 -0.167458 -0.0201657 0.070344 -0.161735 -0.0237508 0.0785256 -0.157925 -0.0237508 0.0805584 -0.162013 -0.0163769 0.095281 -0.151331 -0.0201657 0.101198 -0.144449 -0.0237508 0.108075 -0.139378 -0.0237508 0.109581 -0.141321 -0.0201657 0.11619 -0.13594 -0.0201657 0.120744 -0.128559 -0.0237508 0.126526 -0.122873 -0.0237508 0.128289 -0.124585 -0.0201657 0.133776 -0.118674 -0.0201657 0.13889 -0.112646 -0.0201657 0.143636 -0.106528 -0.0201657 0.153597 -0.0866862 -0.0237508 0.155738 -0.0878945 -0.0201657 0.14996 -0.0928354 -0.0237508 0.157573 -0.0889303 -0.0163769 0.159093 -0.0816643 -0.0201657 0.162129 -0.0754578 -0.0201657 0.166801 -0.0701083 -0.0163769 0.169267 -0.0639259 -0.0163769 0.171451 -0.0578135 -0.0163769 0.175032 -0.0458443 -0.0163769 0.176458 -0.0400067 -0.0163769 0.177659 -0.0342775 -0.0163769 0.178651 -0.0286627 -0.0163769 0.179447 -0.0231674 -0.0163769 0.180059 -0.0177955 -0.0163769 0.1805 -0.0125499 -0.0163769 0.180783 -0.00743258 -0.0163769 0.180919 -0.00244497 -0.0163769 0.180919 0.00244497 -0.0163769 0.180783 0.00743258 -0.0163769 0.1805 0.0125499 -0.0163769 0.180059 0.0177955 -0.0163769 0.179447 0.0231674 -0.0163769 0.178651 0.0286627 -0.0163769 0.177659 0.0342775 -0.0163769 0.176458 0.0400067 -0.0163769 0.175032 0.0458443 -0.0163769 0.173368 0.0517828 -0.0163769 0.169267 0.0639259 -0.0163769 0.166801 0.0701083 -0.0163769 0.159093 0.0816643 -0.0201657 0.155738 0.0878945 -0.0201657 0.15205 0.0941293 -0.0201657 0.14802 0.100348 -0.0201657 0.143636 0.106528 -0.0201657 0.13889 0.112646 -0.0201657 0.131937 0.117043 -0.0237508 0.126526 0.122873 -0.0237508 0.128289 0.124585 -0.0201657 0.122427 0.130351 -0.0201657 0.114592 0.134071 -0.0237508 0.108075 0.139378 -0.0237508 0.110873 0.142986 -0.0163769 0.095281 0.151331 -0.0201657 0.0876125 0.155896 -0.0201657 0.0785256 0.157925 -0.0237508 0.070344 0.161735 -0.0237508 0.072165 0.165922 -0.0163769 0.0539239 0.170505 -0.0201657 0.0448775 0.173106 -0.0201657 0.0356445 0.17524 -0.0201657 0.0262611 0.17689 -0.0201657 0.0167657 0.178041 -0.0201657 0.00719823 0.178684 -0.0201657 -0.00236728 0.176354 -0.0237508 -0.0118236 0.175973 -0.0237508 -0.0119884 0.178426 -0.0201657 -0.021229 0.175088 -0.0237508 -0.0217786 0.17962 -0.0163769 -0.0494262 0.171862 -0.0201657 -0.0583664 0.169035 -0.0201657 -0.0670704 0.165775 -0.0201657 -0.0744708 0.159877 -0.0237508 -0.0825056 0.155882 -0.0237508 -0.0836556 0.158055 -0.0201657 -0.0914884 0.153654 -0.0201657 -0.0989883 0.148933 -0.0201657 -0.107391 0.14562 -0.0163769 -0.119355 0.133169 -0.0201657 -0.126883 0.128991 -0.0163769 -0.137987 0.117036 -0.0163769 -0.147592 0.104664 -0.0163769 -0.153936 0.0910126 -0.0201657 -0.157456 0.0847776 -0.0201657 -0.16065 0.078557 -0.0201657 -0.17423 0.0488015 -0.0163769 -0.175774 0.0429124 -0.0163769 -0.170433 0.0541491 -0.0201657 -0.168409 0.0601513 -0.0201657 -0.177086 0.0371282 -0.0163769 -0.179073 0.0258999 -0.0163769 -0.176105 0.0310891 -0.0201657 -0.177681 0.0202275 -0.0201657 -0.1782 0.0149802 -0.0201657 -0.180869 0.00492252 -0.0163769 -0.180661 0.00997508 -0.0163769 -0.178557 -0.0098589 -0.0201657 -0.167257 -0.00455206 -0.0328772 -0.170509 -0.00464057 -0.0301473 -0.168724 0 -0.0317613 -0.17249 -0.0196365 -0.0270916 -0.169973 -0.0142886 -0.0301473 -0.169478 -0.0192936 -0.0301473 -0.166943 -0.0350016 -0.0301473 -0.168651 -0.0411735 -0.0270916 -0.16991 -0.0356236 -0.0270916 -0.172201 -0.0482331 -0.0201657 -0.163829 -0.0653183 -0.0237508 -0.163531 -0.0723687 -0.0201657 -0.16065 -0.078557 -0.0201657 -0.15182 -0.0897614 -0.0237508 -0.148016 -0.0959054 -0.0237508 -0.145873 -0.103445 -0.0201657 -0.132395 -0.112293 -0.0270916 -0.12725 -0.118092 -0.0270916 -0.129278 -0.119974 -0.0237508 -0.123681 -0.125736 -0.0237508 -0.115868 -0.129279 -0.0270916 -0.109632 -0.134607 -0.0270916 -0.111379 -0.136752 -0.0237508 -0.104681 -0.141945 -0.0237508 -0.0976275 -0.146885 -0.0237508 -0.0902308 -0.151542 -0.0237508 -0.0812116 -0.153437 -0.0270916 -0.0733028 -0.157369 -0.0270916 -0.0755088 -0.162105 -0.0201657 -0.0575641 -0.166712 -0.0237508 -0.0487468 -0.1695 -0.0237508 -0.0397284 -0.171837 -0.0237508 -0.0305435 -0.173705 -0.0237508 -0.021229 -0.175088 -0.0237508 -0.0116382 -0.173213 -0.0270916 -0.00233015 -0.173588 -0.0270916 -0.00236728 -0.176354 -0.0237508 0.00698793 -0.173463 -0.0270916 0.00719823 -0.178684 -0.0201657 0.0351545 -0.172831 -0.0237508 0.0442606 -0.170726 -0.0237508 0.0531826 -0.168161 -0.0237508 0.0618873 -0.165156 -0.0237508 0.0713245 -0.163989 -0.0201657 0.0864082 -0.153753 -0.0237508 0.0939712 -0.149251 -0.0237508 0.102608 -0.146462 -0.0201657 0.114592 -0.134071 -0.0237508 0.122427 -0.130351 -0.0201657 0.129868 -0.115207 -0.0270916 0.134833 -0.109355 -0.0270916 0.136981 -0.111097 -0.0237508 0.13944 -0.103416 -0.0270916 0.143695 -0.0974165 -0.0270916 0.145985 -0.0989687 -0.0237508 0.14802 -0.100348 -0.0201657 0.15205 -0.0941293 -0.0201657 0.160042 -0.0672673 -0.0270916 0.162592 -0.0683392 -0.0237508 0.157392 -0.0732532 -0.0270916 0.164858 -0.0692917 -0.0201657 0.167295 -0.0631813 -0.0201657 0.167939 -0.0439866 -0.0270916 0.170615 -0.0446875 -0.0237508 0.166342 -0.0496845 -0.0270916 0.172993 -0.0453104 -0.0201657 0.174402 -0.0395408 -0.0201657 0.17559 -0.0338783 -0.0201657 0.17657 -0.0283289 -0.0201657 0.177357 -0.0228976 -0.0201657 0.177961 -0.0175882 -0.0201657 0.178398 -0.0124037 -0.0201657 0.178678 -0.00734601 -0.0201657 0.178812 -0.00241649 -0.0201657 0.178812 0.00241649 -0.0201657 0.178678 0.00734601 -0.0201657 0.178398 0.0124037 -0.0201657 0.177961 0.0175882 -0.0201657 0.177357 0.0228976 -0.0201657 0.17657 0.0283289 -0.0201657 0.174402 0.0395408 -0.0201657 0.172993 0.0453104 -0.0201657 0.168993 0.0504761 -0.0237508 0.167125 0.0563546 -0.0237508 0.167295 0.0631813 -0.0201657 0.162592 0.0683392 -0.0237508 0.1599 0.0744205 -0.0237508 0.151188 0.0853266 -0.0270916 0.147608 0.0913793 -0.0270916 0.14996 0.0928354 -0.0237508 0.143695 0.0974165 -0.0270916 0.13944 0.103416 -0.0270916 0.141662 0.105064 -0.0237508 0.136981 0.111097 -0.0237508 0.133776 0.118674 -0.0201657 0.120744 0.128559 -0.0237508 0.11619 0.13594 -0.0201657 0.101198 0.144449 -0.0237508 0.0939712 0.149251 -0.0237508 0.0850529 0.151342 -0.0270916 0.077294 0.155448 -0.0270916 0.0796201 0.160126 -0.0201657 0.0618873 0.165156 -0.0237508 0.0531826 0.168161 -0.0237508 0.0442606 0.170726 -0.0237508 0.0351545 0.172831 -0.0237508 0.0259001 0.174458 -0.0237508 0.0162759 0.172839 -0.0270916 0.00698793 0.173463 -0.0270916 0.00709928 0.176227 -0.0237508 -0.00233015 0.173588 -0.0270916 -0.00240027 0.178812 -0.0201657 -0.0305435 0.173705 -0.0237508 -0.0397284 0.171837 -0.0237508 -0.0487468 0.1695 -0.0237508 -0.0575641 0.166712 -0.0237508 -0.0651109 0.160931 -0.0270916 -0.0733028 0.157369 -0.0270916 -0.0755088 0.162105 -0.0201657 -0.0902308 0.151542 -0.0237508 -0.0960963 0.144582 -0.0270916 -0.103039 0.139719 -0.0270916 -0.104681 0.141945 -0.0237508 -0.111379 0.136752 -0.0237508 -0.115868 0.129279 -0.0270916 -0.121741 0.123764 -0.0270916 -0.123681 0.125736 -0.0237508 -0.129278 0.119974 -0.0237508 -0.134505 0.114083 -0.0237508 -0.139366 0.10809 -0.0237508 -0.143867 0.102023 -0.0237508 -0.148016 0.0959054 -0.0237508 -0.152856 0.0823008 -0.0270916 -0.155957 0.0762619 -0.0270916 -0.15182 0.0897614 -0.0237508 -0.172201 0.0482331 -0.0201657 -0.173726 0.0424126 -0.0201657 -0.166094 0.0593244 -0.0237508 -0.16809 0.0534047 -0.0237508 -0.175023 0.0366957 -0.0201657 -0.176987 0.0255982 -0.0201657 -0.17575 0.0147743 -0.0237508 -0.178557 0.0098589 -0.0201657 -0.175238 0.0199494 -0.0237508 -0.178762 0.00486518 -0.0201657 -0.161064 0 -0.0368271 -0.163825 -0.00445866 -0.0352405 -0.16374 0 -0.0353297 -0.176102 -0.00972337 -0.0237508 -0.17575 -0.0147743 -0.0237508 -0.175238 -0.0199494 -0.0237508 -0.174554 -0.0252463 -0.0237508 -0.166245 -0.0189256 -0.0328772 -0.165596 -0.0239507 -0.0328772 -0.168816 -0.0244164 -0.0301473 -0.172617 -0.0361913 -0.0237508 -0.171338 -0.0418296 -0.0237508 -0.158444 -0.0631711 -0.0301473 -0.155981 -0.0690277 -0.0301473 -0.158753 -0.0702544 -0.0270916 -0.161283 -0.0713739 -0.0237508 -0.155957 -0.0762619 -0.0270916 -0.152856 -0.0823008 -0.0270916 -0.149439 -0.0883536 -0.0270916 -0.145694 -0.0944012 -0.0270916 -0.141611 -0.100422 -0.0270916 -0.137181 -0.106395 -0.0270916 -0.134505 -0.114083 -0.0237508 -0.121741 -0.123764 -0.0270916 -0.117714 -0.131339 -0.0237508 -0.103039 -0.139719 -0.0270916 -0.0960963 -0.144582 -0.0270916 -0.0872647 -0.14656 -0.0301473 -0.0797935 -0.150758 -0.0301473 -0.0825056 -0.155882 -0.0237508 -0.0651109 -0.160931 -0.0270916 -0.0566612 -0.164097 -0.0270916 -0.0479822 -0.166841 -0.0270916 -0.0391053 -0.169142 -0.0270916 -0.0295395 -0.167995 -0.0301473 -0.0205312 -0.169332 -0.0301473 -0.0208961 -0.172342 -0.0270916 -0.0114349 -0.170189 -0.0301473 -0.0118236 -0.175973 -0.0237508 0.0162759 -0.172839 -0.0270916 0.0254939 -0.171722 -0.0270916 0.0346031 -0.17012 -0.0270916 0.0435664 -0.168049 -0.0270916 0.0514344 -0.162633 -0.0301473 0.0598529 -0.159727 -0.0301473 0.0609166 -0.162565 -0.0270916 0.0680317 -0.156418 -0.0301473 0.0692407 -0.159198 -0.0270916 0.077294 -0.155448 -0.0270916 0.0850529 -0.151342 -0.0270916 0.0908822 -0.144345 -0.0301473 0.0978714 -0.1397 -0.0301473 0.0996107 -0.142183 -0.0270916 0.10638 -0.137192 -0.0270916 0.112795 -0.131968 -0.0270916 0.11885 -0.126543 -0.0270916 0.124541 -0.120946 -0.0270916 0.131937 -0.117043 -0.0237508 0.141662 -0.105064 -0.0237508 0.147608 -0.0913793 -0.0270916 0.151188 -0.0853266 -0.0270916 0.156906 -0.0805417 -0.0237508 0.1599 -0.0744205 -0.0237508 0.164996 -0.0623128 -0.0237508 0.167125 -0.0563546 -0.0237508 0.168993 -0.0504761 -0.0237508 0.172005 -0.0389972 -0.0237508 0.173176 -0.0334125 -0.0237508 0.174143 -0.0279395 -0.0237508 0.174918 -0.0225828 -0.0237508 0.175515 -0.0173465 -0.0237508 0.175945 -0.0122332 -0.0237508 0.176221 -0.00724503 -0.0237508 0.176354 -0.00238327 -0.0237508 0.176354 0.00238327 -0.0237508 0.176221 0.00724503 -0.0237508 0.175945 0.0122332 -0.0237508 0.175515 0.0173465 -0.0237508 0.174918 0.0225828 -0.0237508 0.166351 0.0377153 -0.0301473 0.163178 0.0369959 -0.0328772 0.165007 0.0432185 -0.0301473 0.172005 0.0389972 -0.0237508 0.170615 0.0446875 -0.0237508 0.161631 0.0545021 -0.0301473 0.159572 0.0602645 -0.0301473 0.162408 0.0613355 -0.0270916 0.164996 0.0623128 -0.0237508 0.154644 0.0719741 -0.0301473 0.151748 0.0778942 -0.0301473 0.154445 0.0792785 -0.0270916 0.156906 0.0805417 -0.0237508 0.153597 0.0866862 -0.0237508 0.145985 0.0989687 -0.0237508 0.132478 0.107445 -0.0301473 0.1276 0.113195 -0.0301473 0.129868 0.115207 -0.0270916 0.124541 0.120946 -0.0270916 0.116775 0.124333 -0.0301473 0.110826 0.129664 -0.0301473 0.112795 0.131968 -0.0270916 0.10638 0.137192 -0.0270916 0.0996107 0.142183 -0.0270916 0.0908822 0.144345 -0.0301473 0.0835678 0.148699 -0.0301473 0.0864082 0.153753 -0.0237508 0.0692407 0.159198 -0.0270916 0.0609166 0.162565 -0.0270916 0.0523485 0.165523 -0.0270916 0.0435664 0.168049 -0.0270916 0.0339989 0.16715 -0.0301473 0.0250487 0.168723 -0.0301473 0.0254939 0.171722 -0.0270916 0.0159917 0.169821 -0.0301473 0.0165352 0.175593 -0.0237508 -0.0116382 0.173213 -0.0270916 -0.0208961 0.172342 -0.0270916 -0.0300645 0.170981 -0.0270916 -0.0391053 0.169142 -0.0270916 -0.0479822 0.166841 -0.0270916 -0.0556719 0.161232 -0.0301473 -0.063974 0.158121 -0.0301473 -0.0661484 0.163496 -0.0237508 -0.0812116 0.153437 -0.0270916 -0.0888156 0.149165 -0.0270916 -0.0976275 0.146885 -0.0237508 -0.109632 0.134607 -0.0270916 -0.117714 0.131339 -0.0237508 -0.12725 0.118092 -0.0270916 -0.132395 0.112293 -0.0270916 -0.137181 0.106395 -0.0270916 -0.141611 0.100422 -0.0270916 -0.145694 0.0944012 -0.0270916 -0.155291 0.0836122 -0.0237508 -0.162565 0.0516492 -0.0301473 -0.164251 0.0460063 -0.0301473 -0.149439 0.0883536 -0.0270916 -0.169834 0.04757 -0.0237508 -0.171338 0.0418296 -0.0237508 -0.165454 0.0525671 -0.0270916 -0.163488 0.058394 -0.0270916 -0.173685 0.0306617 -0.0237508 -0.172617 0.0361913 -0.0237508 -0.174554 0.0252463 -0.0237508 -0.17096 0.0301808 -0.0270916 -0.17249 0.0196365 -0.0270916 -0.172994 0.0145426 -0.0270916 -0.176102 0.00972337 -0.0237508 -0.176305 0.0047983 -0.0237508 -0.17334 -0.00957087 -0.0270916 -0.172994 -0.0145426 -0.0270916 -0.171816 -0.0248504 -0.0270916 -0.17096 -0.0301808 -0.0270916 -0.163488 -0.058394 -0.0270916 -0.16126 -0.0642938 -0.0270916 -0.146829 -0.0868108 -0.0301473 -0.150187 -0.0808637 -0.0301473 -0.147322 -0.0793213 -0.0328772 -0.139138 -0.0986689 -0.0301473 -0.14315 -0.0927528 -0.0301473 -0.14042 -0.0909836 -0.0328772 -0.134785 -0.104537 -0.0301473 -0.130084 -0.110333 -0.0301473 -0.125028 -0.11603 -0.0301473 -0.113845 -0.127021 -0.0301473 -0.119615 -0.121603 -0.0301473 -0.117334 -0.119283 -0.0328772 -0.107718 -0.132257 -0.0301473 -0.10124 -0.137279 -0.0301473 -0.0944183 -0.142057 -0.0301473 -0.0926173 -0.139347 -0.0328772 -0.0888156 -0.149165 -0.0270916 -0.0720228 -0.154621 -0.0301473 -0.063974 -0.158121 -0.0301473 -0.0556719 -0.161232 -0.0301473 -0.0384224 -0.166189 -0.0301473 -0.0471444 -0.163928 -0.0301473 -0.0462451 -0.160801 -0.0328772 -0.0376896 -0.163019 -0.0328772 -0.0300645 -0.170981 -0.0270916 -0.00228946 -0.170557 -0.0301473 0.00686591 -0.170434 -0.0301473 0.0159917 -0.169821 -0.0301473 0.0250487 -0.168723 -0.0301473 0.0339989 -0.16715 -0.0301473 0.0428057 -0.165114 -0.0301473 0.0419892 -0.161965 -0.0328772 0.0523485 -0.165523 -0.0270916 0.0759443 -0.152733 -0.0301473 0.0835678 -0.148699 -0.0301473 0.0924973 -0.14691 -0.0270916 0.104522 -0.134797 -0.0301473 0.116775 -0.124333 -0.0301473 0.110826 -0.129664 -0.0301473 0.108712 -0.127191 -0.0328772 0.122366 -0.118834 -0.0301473 0.1276 -0.113195 -0.0301473 0.132478 -0.107445 -0.0301473 0.137005 -0.10161 -0.0301473 0.141186 -0.0957154 -0.0301473 0.145031 -0.0897837 -0.0301473 0.148548 -0.0838367 -0.0301473 0.154445 -0.0792785 -0.0270916 0.154644 -0.0719741 -0.0301473 0.157247 -0.0660928 -0.0301473 0.162408 -0.0613355 -0.0270916 0.164503 -0.0554707 -0.0270916 0.164289 -0.0316978 -0.0328772 0.160918 -0.0310475 -0.0352405 0.165206 -0.0265056 -0.0328772 0.169307 -0.0383856 -0.0270916 0.17046 -0.0328885 -0.0270916 0.171412 -0.0275013 -0.0270916 0.172175 -0.0222286 -0.0270916 0.172762 -0.0170744 -0.0270916 0.173186 -0.0120413 -0.0270916 0.173457 -0.0071314 -0.0270916 0.173588 -0.00234589 -0.0270916 0.173588 0.00234589 -0.0270916 0.173457 0.0071314 -0.0270916 0.173186 0.0120413 -0.0270916 0.172762 0.0170744 -0.0270916 0.172175 0.0222286 -0.0270916 0.171412 0.0275013 -0.0270916 0.17046 0.0328885 -0.0270916 0.169307 0.0383856 -0.0270916 0.167939 0.0439866 -0.0270916 0.166342 0.0496845 -0.0270916 0.164503 0.0554707 -0.0270916 0.160042 0.0672673 -0.0270916 0.157392 0.0732532 -0.0270916 0.148548 0.0838367 -0.0301473 0.145031 0.0897837 -0.0301473 0.141186 0.0957154 -0.0301473 0.137005 0.10161 -0.0301473 0.134833 0.109355 -0.0270916 0.122366 0.118834 -0.0301473 0.11885 0.126543 -0.0270916 0.104522 0.134797 -0.0301473 0.0978714 0.1397 -0.0301473 0.0960045 0.137036 -0.0328772 0.0924973 0.14691 -0.0270916 0.0759443 0.152733 -0.0301473 0.0680317 0.156418 -0.0301473 0.0598529 0.159727 -0.0301473 0.0514344 0.162633 -0.0301473 0.0428057 0.165114 -0.0301473 0.0419892 0.161965 -0.0328772 0.0346031 0.17012 -0.0270916 0.00686591 0.170434 -0.0301473 -0.00228946 0.170557 -0.0301473 -0.0114349 0.170189 -0.0301473 -0.0205312 0.169332 -0.0301473 -0.0295395 0.167995 -0.0301473 -0.0384224 0.166189 -0.0301473 -0.0471444 0.163928 -0.0301473 -0.0462451 0.160801 -0.0328772 -0.0566612 0.164097 -0.0270916 -0.0720228 0.154621 -0.0301473 -0.0797935 0.150758 -0.0301473 -0.0944183 0.142057 -0.0301473 -0.0872647 0.14656 -0.0301473 -0.0856002 0.143765 -0.0328772 -0.10124 0.137279 -0.0301473 -0.107718 0.132257 -0.0301473 -0.113845 0.127021 -0.0301473 -0.119615 0.121603 -0.0301473 -0.130084 0.110333 -0.0301473 -0.125028 0.11603 -0.0301473 -0.122643 0.113817 -0.0328772 -0.139138 0.0986689 -0.0301473 -0.134785 0.104537 -0.0301473 -0.132214 0.102543 -0.0328772 -0.146829 0.0868108 -0.0301473 -0.14315 0.0927528 -0.0301473 -0.14042 0.0909836 -0.0328772 -0.153233 0.0749303 -0.0301473 -0.16717 0.0468239 -0.0270916 -0.168651 0.0411735 -0.0270916 -0.16991 0.0356236 -0.0270916 -0.171816 0.0248504 -0.0270916 -0.167975 0.0296538 -0.0301473 -0.169478 0.0192936 -0.0301473 -0.169973 0.0142886 -0.0301473 -0.17354 0.00472304 -0.0270916 -0.17334 0.00957087 -0.0270916 -0.149356 0 -0.0402051 -0.149162 -0.00405959 -0.0402139 -0.152399 0 -0.0398278 -0.170313 -0.00940375 -0.0301473 -0.156595 -0.00426189 -0.0387046 -0.15538 0 -0.0391121 -0.152883 -0.00416085 -0.039724 -0.167975 -0.0296538 -0.0301473 -0.16139 -0.0284914 -0.0352405 -0.157875 -0.0278708 -0.0371966 -0.160398 -0.0336295 -0.0352405 -0.160634 -0.0573743 -0.0301473 -0.149867 -0.0663217 -0.0352405 -0.15031 -0.073501 -0.0328772 -0.153006 -0.067711 -0.0328772 -0.153233 -0.0749303 -0.0301473 -0.129501 -0.100439 -0.0352405 -0.127602 -0.108228 -0.0328772 -0.132214 -0.102543 -0.0328772 -0.111673 -0.124598 -0.0328772 -0.0972711 -0.131898 -0.0352405 -0.0993087 -0.13466 -0.0328772 -0.0856002 -0.143765 -0.0328772 -0.0782715 -0.147882 -0.0328772 -0.0614661 -0.151923 -0.0352405 -0.0546099 -0.158156 -0.0328772 -0.0627537 -0.155105 -0.0328772 -0.0534895 -0.154911 -0.0352405 -0.028976 -0.164791 -0.0328772 -0.0201396 -0.166103 -0.0328772 -0.0112168 -0.166943 -0.0328772 -0.00224579 -0.167304 -0.0328772 0.00673495 -0.167183 -0.0328772 0.0156866 -0.166582 -0.0328772 0.0326661 -0.160597 -0.0352405 0.0333504 -0.163962 -0.0328772 0.0504533 -0.159531 -0.0328772 0.0587112 -0.15668 -0.0328772 0.066734 -0.153435 -0.0328772 0.0802918 -0.14287 -0.0352405 0.0891487 -0.141592 -0.0328772 0.0819738 -0.145863 -0.0328772 0.0960045 -0.137036 -0.0328772 0.11757 -0.114175 -0.0352405 0.125166 -0.111036 -0.0328772 0.120032 -0.116567 -0.0328772 0.134392 -0.0996722 -0.0328772 0.148854 -0.0764084 -0.0328772 0.145714 -0.0822375 -0.0328772 0.142724 -0.0805502 -0.0352405 0.151748 -0.0778942 -0.0301473 0.155295 -0.0523656 -0.0352405 0.153317 -0.0579021 -0.0352405 0.149977 -0.0566409 -0.0371966 0.159572 -0.0602645 -0.0301473 0.161631 -0.0545021 -0.0301473 0.163438 -0.0488169 -0.0301473 0.165007 -0.0432185 -0.0301473 0.166351 -0.0377153 -0.0301473 0.167484 -0.0323142 -0.0301473 0.168419 -0.027021 -0.0301473 0.169169 -0.0218405 -0.0301473 0.169746 -0.0167762 -0.0301473 0.170162 -0.0118311 -0.0301473 0.170429 -0.00700687 -0.0301473 0.170557 -0.00230493 -0.0301473 0.170557 0.00230493 -0.0301473 0.170429 0.00700687 -0.0301473 0.170162 0.0118311 -0.0301473 0.169746 0.0167762 -0.0301473 0.169169 0.0218405 -0.0301473 0.168419 0.027021 -0.0301473 0.167484 0.0323142 -0.0301473 0.163438 0.0488169 -0.0301473 0.153317 0.0579021 -0.0352405 0.154248 0.0648321 -0.0328772 0.156528 0.059115 -0.0328772 0.157247 0.0660928 -0.0301473 0.151694 0.0706013 -0.0328772 0.145714 0.0822375 -0.0328772 0.138493 0.0938897 -0.0328772 0.129951 0.105396 -0.0328772 0.11757 0.114175 -0.0352405 0.114547 0.121961 -0.0328772 0.120032 0.116567 -0.0328772 0.108712 0.127191 -0.0328772 0.0891487 0.141592 -0.0328772 0.0819738 0.145863 -0.0328772 0.0744957 0.14982 -0.0328772 0.0575066 0.153465 -0.0352405 0.0504533 0.159531 -0.0328772 0.0587112 0.15668 -0.0328772 0.0494182 0.156258 -0.0352405 0.0333504 0.163962 -0.0328772 0.0245709 0.165505 -0.0328772 0.0156866 0.166582 -0.0328772 0.00673495 0.167183 -0.0328772 -0.00224579 0.167304 -0.0328772 -0.0112168 0.166943 -0.0328772 -0.0283815 0.16141 -0.0352405 -0.0376896 0.163019 -0.0328772 -0.028976 0.164791 -0.0328772 -0.0369163 0.159674 -0.0352405 -0.0546099 0.158156 -0.0328772 -0.0627537 0.155105 -0.0328772 -0.0766656 0.144848 -0.0352405 -0.0782715 0.147882 -0.0328772 -0.0926173 0.139347 -0.0328772 -0.103495 0.127072 -0.0352405 -0.111673 0.124598 -0.0328772 -0.105663 0.129734 -0.0328772 -0.147226 0.071993 -0.0352405 -0.153006 0.067711 -0.0328772 -0.15031 0.073501 -0.0328772 -0.155981 0.0690277 -0.0301473 -0.165706 0.0404546 -0.0301473 -0.168816 0.0244164 -0.0301473 -0.164771 0.0290882 -0.0328772 -0.166943 0.0350016 -0.0301473 -0.166245 0.0189256 -0.0328772 -0.166731 0.0140161 -0.0328772 -0.170509 0.00464057 -0.0301473 -0.170313 0.00940375 -0.0301473 -0.166295 0 -0.0336341 -0.167065 -0.00922437 -0.0328772 -0.166731 -0.0140161 -0.0328772 -0.152402 -0.0128115 -0.039724 -0.151958 -0.0172991 -0.039724 -0.155648 -0.0177192 -0.0387046 -0.164771 -0.0290882 -0.0328772 -0.163758 -0.034334 -0.0328772 -0.155421 -0.0619662 -0.0328772 -0.144299 -0.0776938 -0.0352405 -0.144029 -0.0851549 -0.0328772 -0.137538 -0.0891168 -0.0352405 -0.136484 -0.0967869 -0.0328772 -0.11751 -0.109054 -0.0371966 -0.114926 -0.116836 -0.0352405 -0.120127 -0.111482 -0.0352405 -0.122643 -0.113817 -0.0328772 -0.101241 -0.124305 -0.0371966 -0.103495 -0.127072 -0.0352405 -0.105663 -0.129734 -0.0328772 -0.090717 -0.136488 -0.0352405 -0.0838439 -0.140815 -0.0352405 -0.0676922 -0.145324 -0.0371966 -0.0691994 -0.14856 -0.0352405 -0.070649 -0.151672 -0.0328772 -0.0452963 -0.157502 -0.0352405 -0.0369163 -0.159674 -0.0352405 -0.0283815 -0.16141 -0.0352405 -0.0197263 -0.162694 -0.0352405 -0.0109867 -0.163517 -0.0352405 0.00645308 -0.160187 -0.0371966 0.0153648 -0.163164 -0.0352405 0.00659676 -0.163753 -0.0352405 0.0150301 -0.15961 -0.0371966 0.0240668 -0.162109 -0.0352405 0.0235426 -0.158578 -0.0371966 0.0245709 -0.165505 -0.0328772 0.0411277 -0.158642 -0.0352405 0.0494182 -0.156258 -0.0352405 0.0575066 -0.153465 -0.0352405 0.071378 -0.14355 -0.0371966 0.0729673 -0.146746 -0.0352405 0.0744957 -0.14982 -0.0328772 0.0873196 -0.138686 -0.0352405 0.0982376 -0.126692 -0.0371966 0.106481 -0.124581 -0.0352405 0.100425 -0.129512 -0.0352405 0.102529 -0.132225 -0.0328772 0.114547 -0.121961 -0.0328772 0.124513 -0.100985 -0.0371966 0.131634 -0.0976272 -0.0352405 0.127285 -0.103233 -0.0352405 0.129951 -0.105396 -0.0328772 0.132697 -0.0899603 -0.0371966 0.139345 -0.0862641 -0.0352405 0.135652 -0.0919633 -0.0352405 0.138493 -0.0938897 -0.0328772 0.142264 -0.0880711 -0.0328772 0.151694 -0.0706013 -0.0328772 0.154248 -0.0648321 -0.0328772 0.156528 -0.059115 -0.0328772 0.158548 -0.0534625 -0.0328772 0.16032 -0.0478857 -0.0328772 0.161859 -0.0423942 -0.0328772 0.163178 -0.0369959 -0.0328772 0.165942 -0.0214239 -0.0328772 0.166508 -0.0164563 -0.0328772 0.166916 -0.0116054 -0.0328772 0.167178 -0.00687322 -0.0328772 0.167304 -0.00226096 -0.0328772 0.167304 0.00226096 -0.0328772 0.167178 0.00687322 -0.0328772 0.166916 0.0116054 -0.0328772 0.166508 0.0164563 -0.0328772 0.165942 0.0214239 -0.0328772 0.165206 0.0265056 -0.0328772 0.164289 0.0316978 -0.0328772 0.155085 0.0406199 -0.0371966 0.157031 0.0469032 -0.0352405 0.158538 0.0415243 -0.0352405 0.161859 0.0423942 -0.0328772 0.16032 0.0478857 -0.0328772 0.158548 0.0534625 -0.0328772 0.142624 0.0732106 -0.0371966 0.142724 0.0805502 -0.0352405 0.1458 0.0748407 -0.0352405 0.148854 0.0764084 -0.0328772 0.13631 0.0843852 -0.0371966 0.135652 0.0919633 -0.0352405 0.139345 0.0862641 -0.0352405 0.142264 0.0880711 -0.0328772 0.128767 0.0955008 -0.0371966 0.127285 0.103233 -0.0352405 0.131634 0.0976272 -0.0352405 0.134392 0.0996722 -0.0328772 0.125166 0.111036 -0.0328772 0.112197 0.119459 -0.0352405 0.0982376 0.126692 -0.0371966 0.0940347 0.134224 -0.0352405 0.100425 0.129512 -0.0352405 0.102529 0.132225 -0.0328772 0.0873196 0.138686 -0.0352405 0.0802918 0.14287 -0.0352405 0.0639411 0.147013 -0.0371966 0.0653648 0.150287 -0.0352405 0.066734 0.153435 -0.0328772 0.0411277 0.158642 -0.0352405 0.0326661 0.160597 -0.0352405 0.0240668 0.162109 -0.0352405 0.0153648 0.163164 -0.0352405 0.00659676 0.163753 -0.0352405 -0.0107474 0.159956 -0.0371966 -0.0197263 0.162694 -0.0352405 -0.0109867 0.163517 -0.0352405 -0.0192967 0.159151 -0.0371966 -0.0201396 0.166103 -0.0328772 -0.0452963 0.157502 -0.0352405 -0.0534895 0.154911 -0.0352405 -0.0676922 0.145324 -0.0371966 -0.0691994 0.14856 -0.0352405 -0.070649 0.151672 -0.0328772 -0.0838439 0.140815 -0.0352405 -0.0951525 0.129025 -0.0371966 -0.0972711 0.131898 -0.0352405 -0.0993087 0.13466 -0.0328772 -0.112423 0.114291 -0.0371966 -0.120127 0.111482 -0.0352405 -0.114926 0.116836 -0.0352405 -0.117334 0.119283 -0.0328772 -0.127602 0.108228 -0.0328772 -0.129501 0.100439 -0.0352405 -0.136484 0.0967869 -0.0328772 -0.138001 0.0815911 -0.0371966 -0.144299 0.0776938 -0.0352405 -0.141074 0.0834078 -0.0352405 -0.150975 0.0539245 -0.0371966 -0.162545 0.0396829 -0.0328772 -0.163758 0.034334 -0.0328772 -0.165596 0.0239507 -0.0328772 -0.16139 0.0284914 -0.0352405 -0.162834 0.0185373 -0.0352405 -0.16331 0.0137285 -0.0352405 -0.167257 0.00455206 -0.0328772 -0.167065 0.00922437 -0.0328772 -0.160257 -0.00436155 -0.0371966 -0.163637 -0.00903511 -0.0352405 -0.16331 -0.0137285 -0.0352405 -0.162834 -0.0185373 -0.0352405 -0.162198 -0.0234593 -0.0352405 -0.147526 -0.0526924 -0.0387046 -0.148917 -0.0593728 -0.0371966 -0.150975 -0.0539245 -0.0371966 -0.154337 -0.0551252 -0.0352405 -0.152233 -0.0606948 -0.0352405 -0.146603 -0.0648772 -0.0371966 -0.147226 -0.071993 -0.0352405 -0.134543 -0.0871758 -0.0371966 -0.138001 -0.0815911 -0.0371966 -0.134848 -0.0797268 -0.0387046 -0.141074 -0.0834078 -0.0352405 -0.126681 -0.0982514 -0.0371966 -0.130772 -0.0927362 -0.0371966 -0.127784 -0.0906172 -0.0387046 -0.133684 -0.094801 -0.0352405 -0.124984 -0.106007 -0.0352405 -0.109382 -0.122042 -0.0352405 -0.112423 -0.114291 -0.0371966 -0.0951525 -0.129025 -0.0371966 -0.0887412 -0.133515 -0.0371966 -0.0749957 -0.141693 -0.0371966 -0.0732821 -0.138456 -0.0387046 -0.0766656 -0.144848 -0.0352405 -0.0601274 -0.148614 -0.0371966 -0.0523244 -0.151537 -0.0371966 -0.0443097 -0.154072 -0.0371966 -0.0361122 -0.156196 -0.0371966 -0.0277633 -0.157894 -0.0371966 -0.0021518 -0.160302 -0.0371966 -0.0107474 -0.159956 -0.0371966 -0.0105018 -0.156301 -0.0387046 -0.00210263 -0.156639 -0.0387046 -0.00219971 -0.163871 -0.0352405 0.0319546 -0.1571 -0.0371966 0.0402319 -0.155186 -0.0371966 0.0483418 -0.152854 -0.0371966 0.0639411 -0.147013 -0.0371966 0.0624801 -0.143654 -0.0387046 0.0653648 -0.150287 -0.0352405 0.0785431 -0.139758 -0.0371966 0.0919866 -0.131301 -0.0371966 0.0898847 -0.1283 -0.0387046 0.0940347 -0.134224 -0.0352405 0.115009 -0.111689 -0.0371966 0.109753 -0.116857 -0.0371966 0.107245 -0.114187 -0.0387046 0.112197 -0.119459 -0.0352405 0.122598 -0.108758 -0.0352405 0.139365 -0.0715378 -0.0387046 0.145346 -0.0676465 -0.0371966 0.142624 -0.0732106 -0.0371966 0.1458 -0.0748407 -0.0352405 0.148582 -0.0691527 -0.0352405 0.151083 -0.0635019 -0.0352405 0.157031 -0.0469032 -0.0352405 0.158538 -0.0415243 -0.0352405 0.15983 -0.0362368 -0.0352405 0.158997 -0.0205273 -0.0371966 0.163091 -0.0161186 -0.0352405 0.162537 -0.0209843 -0.0352405 0.161817 -0.0259618 -0.0352405 0.163491 -0.0113673 -0.0352405 0.163748 -0.0067322 -0.0352405 0.163871 -0.00221457 -0.0352405 0.163871 0.00221457 -0.0352405 0.163748 0.0067322 -0.0352405 0.163491 0.0113673 -0.0352405 0.163091 0.0161186 -0.0352405 0.162537 0.0209843 -0.0352405 0.161817 0.0259618 -0.0352405 0.160918 0.0310475 -0.0352405 0.15983 0.0362368 -0.0352405 0.155295 0.0523656 -0.0352405 0.144416 0.0606994 -0.0387046 0.145346 0.0676465 -0.0371966 0.147793 0.0621188 -0.0371966 0.151083 0.0635019 -0.0352405 0.148582 0.0691527 -0.0352405 0.115009 0.111689 -0.0371966 0.119928 0.106389 -0.0371966 0.117188 0.103958 -0.0387046 0.122598 0.108758 -0.0352405 0.104162 0.121867 -0.0371966 0.101782 0.119083 -0.0387046 0.106481 0.124581 -0.0352405 0.0919866 0.131301 -0.0371966 0.071378 0.14355 -0.0371966 0.0785431 0.139758 -0.0371966 0.0767484 0.136565 -0.0387046 0.069747 0.14027 -0.0387046 0.0729673 0.146746 -0.0352405 0.0562541 0.150123 -0.0371966 0.0483418 0.152854 -0.0371966 0.0402319 0.155186 -0.0371966 0.0319546 0.1571 -0.0371966 0.00645308 0.160187 -0.0371966 0.0150301 0.15961 -0.0371966 0.0146867 0.155963 -0.0387046 -0.0021518 0.160302 -0.0371966 0.00630563 0.156526 -0.0387046 -0.00210263 0.156639 -0.0387046 -0.00219971 0.163871 -0.0352405 -0.0277633 0.157894 -0.0371966 -0.0361122 0.156196 -0.0371966 -0.0443097 0.154072 -0.0371966 -0.0601274 0.148614 -0.0371966 -0.0587535 0.145218 -0.0387046 -0.0614661 0.151923 -0.0352405 -0.0749957 0.141693 -0.0371966 -0.090717 0.136488 -0.0352405 -0.0820177 0.137748 -0.0371966 -0.101241 0.124305 -0.0371966 -0.109382 0.122042 -0.0352405 -0.126681 0.0982514 -0.0371966 -0.122262 0.103699 -0.0371966 -0.119468 0.101329 -0.0387046 -0.124984 0.106007 -0.0352405 -0.134543 0.0871758 -0.0371966 -0.130772 0.0927362 -0.0371966 -0.127784 0.0906172 -0.0387046 -0.133684 0.094801 -0.0352405 -0.137538 0.0891168 -0.0352405 -0.143253 0.0633948 -0.0387046 -0.148917 0.0593728 -0.0371966 -0.146603 0.0648772 -0.0371966 -0.149867 0.0663217 -0.0352405 -0.152233 0.0606948 -0.0352405 -0.15921 0.0388687 -0.0352405 -0.160398 0.0336295 -0.0352405 -0.162198 0.0234593 -0.0352405 -0.157875 0.0278708 -0.0371966 -0.163637 0.00903511 -0.0352405 -0.163825 0.00445866 -0.0352405 -0.158274 0 -0.0380982 -0.160073 -0.00883832 -0.0371966 -0.159753 -0.0134295 -0.0371966 -0.159288 -0.0181336 -0.0371966 -0.158666 -0.0229483 -0.0371966 -0.151364 -0.0218924 -0.039724 -0.14826 -0.0168781 -0.0402139 -0.147681 -0.0213596 -0.0402139 -0.15061 -0.0265883 -0.039724 -0.154375 -0.0432401 -0.0371966 -0.15279 -0.0485437 -0.0371966 -0.137393 -0.0671843 -0.039724 -0.137931 -0.074265 -0.0387046 -0.140729 -0.0688158 -0.0387046 -0.14402 -0.0704249 -0.0371966 -0.141156 -0.0760016 -0.0371966 -0.116636 -0.0989267 -0.039724 -0.114825 -0.106562 -0.0387046 -0.119468 -0.101329 -0.0387046 -0.122262 -0.103699 -0.0371966 -0.0989277 -0.121464 -0.0387046 -0.104555 -0.116656 -0.0387046 -0.102076 -0.11389 -0.039724 -0.106999 -0.119384 -0.0371966 -0.0929783 -0.126077 -0.0387046 -0.0801436 -0.1346 -0.0387046 -0.0782436 -0.131409 -0.039724 -0.0820177 -0.137748 -0.0371966 -0.0661455 -0.142004 -0.0387046 -0.0587535 -0.145218 -0.0387046 -0.0511289 -0.148075 -0.0387046 -0.027129 -0.154286 -0.0387046 -0.0352871 -0.152627 -0.0387046 -0.0344505 -0.149009 -0.039724 -0.0188558 -0.155514 -0.0387046 -0.0264858 -0.150629 -0.039724 -0.0184087 -0.151827 -0.039724 -0.0192967 -0.159151 -0.0371966 0.00630563 -0.156526 -0.0387046 0.0146867 -0.155963 -0.0387046 0.0230046 -0.154955 -0.0387046 0.0312245 -0.15351 -0.0387046 0.0549687 -0.146693 -0.0387046 0.0472372 -0.149362 -0.0387046 0.0461173 -0.145821 -0.039724 0.0536655 -0.143215 -0.039724 0.0562541 -0.150123 -0.0371966 0.069747 -0.14027 -0.0387046 0.0767484 -0.136565 -0.0387046 0.0854177 -0.135666 -0.0371966 0.095993 -0.123797 -0.0387046 0.104162 -0.121867 -0.0371966 0.114409 -0.101494 -0.039724 0.121668 -0.0986774 -0.0387046 0.117188 -0.103958 -0.0387046 0.119928 -0.106389 -0.0371966 0.128767 -0.0955008 -0.0371966 0.130038 -0.0805022 -0.039724 0.136426 -0.0769953 -0.0387046 0.133196 -0.0824571 -0.0387046 0.13631 -0.0843852 -0.0371966 0.139616 -0.0787958 -0.0371966 0.147793 -0.0621188 -0.0371966 0.144922 -0.0488679 -0.039724 0.150101 -0.0448333 -0.0387046 0.148441 -0.0500546 -0.0387046 0.151912 -0.051225 -0.0371966 0.153611 -0.0458817 -0.0371966 0.155085 -0.0406199 -0.0371966 0.156348 -0.0354476 -0.0371966 0.157413 -0.0303712 -0.0371966 0.158292 -0.0253963 -0.0371966 0.159539 -0.0157675 -0.0371966 0.15993 -0.0111197 -0.0371966 0.160181 -0.00658557 -0.0371966 0.160302 -0.00216634 -0.0371966 0.160302 0.00216634 -0.0371966 0.160181 0.00658557 -0.0371966 0.155894 0.0154073 -0.0387046 0.158997 0.0205273 -0.0371966 0.159539 0.0157675 -0.0371966 0.15993 0.0111197 -0.0371966 0.158292 0.0253963 -0.0371966 0.157413 0.0303712 -0.0371966 0.156348 0.0354476 -0.0371966 0.146542 0.0437704 -0.039724 0.148441 0.0500546 -0.0387046 0.150101 0.0448333 -0.0387046 0.153611 0.0458817 -0.0371966 0.151912 0.051225 -0.0371966 0.149977 0.0566409 -0.0371966 0.139365 0.0715378 -0.0387046 0.139616 0.0787958 -0.0371966 0.133196 0.0824571 -0.0387046 0.132697 0.0899603 -0.0371966 0.125825 0.0933187 -0.0387046 0.124513 0.100985 -0.0371966 0.112381 0.109137 -0.0387046 0.109753 0.116857 -0.0371966 0.095993 0.123797 -0.0387046 0.0814871 0.129423 -0.039724 0.0834659 0.132566 -0.0387046 0.0854177 0.135666 -0.0371966 0.0624801 0.143654 -0.0387046 0.0549687 0.146693 -0.0387046 0.0472372 0.149362 -0.0387046 0.0230046 0.154955 -0.0387046 0.0312245 0.15351 -0.0387046 0.0304842 0.14987 -0.039724 0.0224592 0.151281 -0.039724 0.0235426 0.158578 -0.0371966 -0.0105018 0.156301 -0.0387046 -0.0188558 0.155514 -0.0387046 -0.027129 0.154286 -0.0387046 -0.0352871 0.152627 -0.0387046 -0.0511289 0.148075 -0.0387046 -0.0499167 0.144564 -0.039724 -0.0523244 0.151537 -0.0371966 -0.0661455 0.142004 -0.0387046 -0.0732821 0.138456 -0.0387046 -0.0929783 0.126077 -0.0387046 -0.0867135 0.130465 -0.0387046 -0.0846577 0.127372 -0.039724 -0.0887412 0.133515 -0.0371966 -0.102076 0.11389 -0.039724 -0.109854 0.111679 -0.0387046 -0.104555 0.116656 -0.0387046 -0.106999 0.119384 -0.0371966 -0.11751 0.109054 -0.0371966 -0.134848 0.0797268 -0.0387046 -0.141156 0.0760016 -0.0371966 -0.14402 0.0704249 -0.0371966 -0.152184 0.0371533 -0.0387046 -0.150848 0.0422521 -0.0387046 -0.155742 0.0380221 -0.0371966 -0.147526 0.0526924 -0.0387046 -0.156905 0.032897 -0.0371966 -0.158666 0.0229483 -0.0371966 -0.159288 0.0181336 -0.0371966 -0.159753 0.0134295 -0.0371966 -0.155648 0.0177192 -0.0387046 -0.156103 0.0131226 -0.0387046 -0.160257 0.00436155 -0.0371966 -0.160073 0.00883832 -0.0371966 -0.131993 0 -0.0351034 -0.134875 -0.00367074 -0.0368012 -0.13464 0 -0.0366517 -0.156415 -0.00863637 -0.0387046 -0.156103 -0.0131226 -0.0387046 -0.15504 -0.022424 -0.0387046 -0.154268 -0.027234 -0.0387046 -0.150848 -0.0422521 -0.0387046 -0.149299 -0.0474345 -0.0387046 -0.138607 -0.0552623 -0.0402139 -0.139857 -0.0618918 -0.039724 -0.142064 -0.0566407 -0.039724 -0.145514 -0.0580162 -0.0387046 -0.143253 -0.0633948 -0.0387046 -0.131651 -0.0778366 -0.039724 -0.131469 -0.0851839 -0.0387046 -0.124755 -0.0884689 -0.039724 -0.123786 -0.0960064 -0.0387046 -0.10725 -0.109032 -0.039724 -0.10464 -0.106378 -0.0402139 -0.109854 -0.111679 -0.0387046 -0.0965824 -0.118585 -0.039724 -0.0825975 -0.124272 -0.0402139 -0.0846577 -0.127372 -0.039724 -0.0867135 -0.130465 -0.0387046 -0.0715447 -0.135173 -0.039724 -0.0645773 -0.138637 -0.039724 -0.0573606 -0.141775 -0.039724 -0.0422708 -0.146982 -0.039724 -0.0412421 -0.143405 -0.0402139 -0.0432973 -0.150551 -0.0387046 -0.0102528 -0.152595 -0.039724 -0.00205279 -0.152926 -0.039724 0.00615614 -0.152815 -0.039724 0.0143385 -0.152266 -0.039724 0.0224592 -0.151281 -0.039724 0.0383806 -0.148045 -0.039724 0.0374466 -0.144442 -0.0402139 0.0393126 -0.15164 -0.0387046 0.0609988 -0.140248 -0.039724 0.0680935 -0.136944 -0.039724 0.0795041 -0.126273 -0.0402139 0.0877537 -0.125259 -0.039724 0.0814871 -0.129423 -0.039724 0.0834659 -0.132566 -0.0387046 0.0969506 -0.11343 -0.0402139 0.104703 -0.11148 -0.039724 0.0993688 -0.11626 -0.039724 0.101782 -0.119083 -0.0387046 0.112381 -0.109137 -0.0387046 0.119852 -0.0888891 -0.0402139 0.126591 -0.0858207 -0.039724 0.122842 -0.0911063 -0.039724 0.125825 -0.0933187 -0.0387046 0.129665 -0.0879048 -0.0387046 0.135283 -0.0629632 -0.0402139 0.140992 -0.0592603 -0.039724 0.138657 -0.0645337 -0.039724 0.142024 -0.0661008 -0.0387046 0.144416 -0.0606994 -0.0387046 0.14655 -0.0553467 -0.0387046 0.151542 -0.0396918 -0.0387046 0.152776 -0.0346376 -0.0387046 0.153817 -0.0296773 -0.0387046 0.154675 -0.024816 -0.0387046 0.155364 -0.0200582 -0.0387046 0.155894 -0.0154073 -0.0387046 0.156276 -0.0108656 -0.0387046 0.156521 -0.00643509 -0.0387046 0.156639 -0.00211684 -0.0387046 0.156639 0.00211684 -0.0387046 0.156521 0.00643509 -0.0387046 0.156276 0.0108656 -0.0387046 0.146515 0.0282686 -0.0402139 0.142895 0.02757 -0.0401362 0.145524 0.0329935 -0.0402139 0.155364 0.0200582 -0.0387046 0.154675 0.024816 -0.0387046 0.153817 0.0296773 -0.0387046 0.152776 0.0346376 -0.0387046 0.151542 0.0396918 -0.0387046 0.14655 0.0553467 -0.0387046 0.140992 0.0592603 -0.039724 0.142024 0.0661008 -0.0387046 0.12995 0.0733406 -0.0402139 0.130038 0.0805022 -0.039724 0.133191 0.0751699 -0.039724 0.136426 0.0769953 -0.0387046 0.12351 0.0837322 -0.0402139 0.122842 0.0911063 -0.039724 0.126591 0.0858207 -0.039724 0.129665 0.0879048 -0.0387046 0.115893 0.0939936 -0.0402139 0.114409 0.101494 -0.039724 0.118783 0.096338 -0.039724 0.121668 0.0986774 -0.0387046 0.102155 0.108767 -0.0402139 0.0993688 0.11626 -0.039724 0.104703 0.11148 -0.039724 0.107245 0.114187 -0.0387046 0.0877537 0.125259 -0.039724 0.0856182 0.12221 -0.0402139 0.0898847 0.1283 -0.0387046 0.0749288 0.133327 -0.039724 0.0680935 0.136944 -0.039724 0.0609988 0.140248 -0.039724 0.0461173 0.145821 -0.039724 0.044995 0.142272 -0.0402139 0.0383806 0.148045 -0.039724 0.0374466 0.144442 -0.0402139 0.0393126 0.15164 -0.0387046 0.0143385 0.152266 -0.039724 0.00615614 0.152815 -0.039724 -0.00205279 0.152926 -0.039724 -0.0102528 0.152595 -0.039724 -0.0184087 0.151827 -0.039724 -0.0344505 0.149009 -0.039724 -0.0336121 0.145383 -0.0402139 -0.0422708 0.146982 -0.039724 -0.0412421 0.143405 -0.0402139 -0.0432973 0.150551 -0.0387046 -0.0573606 0.141775 -0.039724 -0.0645773 0.138637 -0.039724 -0.0782436 0.131409 -0.039724 -0.0763395 0.128211 -0.0402139 -0.0801436 0.1346 -0.0387046 -0.090774 0.123088 -0.039724 -0.0989277 0.121464 -0.0387046 -0.109375 0.101504 -0.0402139 -0.116636 0.0989267 -0.039724 -0.112103 0.104035 -0.039724 -0.114825 0.106562 -0.0387046 -0.123786 0.0960064 -0.0387046 -0.124755 0.0884689 -0.039724 -0.131469 0.0851839 -0.0387046 -0.131384 0.0707399 -0.0402139 -0.137393 0.0671843 -0.039724 -0.134661 0.0725043 -0.039724 -0.137931 0.074265 -0.0387046 -0.140729 0.0688158 -0.0387046 -0.138607 0.0552623 -0.0402139 -0.144028 0.0514432 -0.039724 -0.142064 0.0566407 -0.039724 -0.145514 0.0580162 -0.0387046 -0.14576 0.0463099 -0.039724 -0.154268 0.027234 -0.0387046 -0.15332 0.0321454 -0.0387046 -0.15504 0.022424 -0.0387046 -0.151958 0.0172991 -0.039724 -0.152402 0.0128115 -0.039724 -0.156595 0.00426189 -0.0387046 -0.156415 0.00863637 -0.0387046 -0.152707 -0.00843162 -0.039724 -0.138314 -0.00376435 -0.0383714 -0.137404 0 -0.0379798 -0.147271 -0.0412503 -0.039724 -0.14576 -0.0463099 -0.039724 -0.144028 -0.0514432 -0.039724 -0.131384 -0.0707399 -0.0402139 -0.128137 -0.0689917 -0.0401362 -0.128447 -0.0759424 -0.0402139 -0.134661 -0.0725043 -0.039724 -0.125228 -0.0811405 -0.0402139 -0.122133 -0.0791353 -0.0401362 -0.121719 -0.0863159 -0.0402139 -0.128352 -0.0831643 -0.039724 -0.117911 -0.0914492 -0.0402139 -0.114997 -0.0891893 -0.0401362 -0.113798 -0.0965193 -0.0402139 -0.120852 -0.0937302 -0.039724 -0.112103 -0.104035 -0.039724 -0.0995917 -0.111119 -0.0402139 -0.0885649 -0.120092 -0.0402139 -0.0863762 -0.117124 -0.0401362 -0.090774 -0.123088 -0.039724 -0.0763395 -0.128211 -0.0402139 -0.0698037 -0.131884 -0.0402139 -0.0559647 -0.138325 -0.0402139 -0.0545816 -0.134907 -0.0401362 -0.0487019 -0.141046 -0.0402139 -0.0474984 -0.13756 -0.0401362 -0.0499167 -0.144564 -0.039724 -0.0336121 -0.145383 -0.0402139 -0.0258412 -0.146963 -0.0402139 -0.0179607 -0.148133 -0.0402139 -0.0100033 -0.148882 -0.0402139 -0.00200283 -0.149204 -0.0402139 0.00600632 -0.149097 -0.0402139 0.0219127 -0.1476 -0.0402139 0.0213712 -0.143952 -0.0401362 0.0297424 -0.146223 -0.0402139 0.0290073 -0.14261 -0.0401362 0.0304842 -0.14987 -0.039724 0.044995 -0.142272 -0.0402139 0.0523595 -0.13973 -0.0402139 0.0595143 -0.136835 -0.0402139 0.0731054 -0.130083 -0.0402139 0.0712987 -0.126868 -0.0401362 0.0749288 -0.133327 -0.039724 0.0856182 -0.12221 -0.0402139 0.0937172 -0.120862 -0.039724 0.102155 -0.108767 -0.0402139 0.109717 -0.106549 -0.039724 0.111625 -0.0990236 -0.0402139 0.118783 -0.096338 -0.039724 0.126873 -0.0785431 -0.0402139 0.133191 -0.0751699 -0.039724 0.136061 -0.0698417 -0.039724 0.143076 -0.0540345 -0.039724 0.133221 -0.0213739 -0.0368012 0.136618 -0.021919 -0.0383714 0.132481 -0.0255609 -0.0368012 0.146542 -0.0437704 -0.039724 0.147949 -0.0387507 -0.039724 0.149154 -0.0338164 -0.039724 0.15017 -0.0289737 -0.039724 0.151008 -0.0242277 -0.039724 0.15168 -0.0195827 -0.039724 0.152198 -0.015042 -0.039724 0.152571 -0.010608 -0.039724 0.15281 -0.00628253 -0.039724 0.152925 -0.00206665 -0.039724 0.152925 0.00206665 -0.039724 0.15281 0.00628253 -0.039724 0.152571 0.010608 -0.039724 0.152198 0.015042 -0.039724 0.15168 0.0195827 -0.039724 0.151008 0.0242277 -0.039724 0.15017 0.0289737 -0.039724 0.149154 0.0338164 -0.039724 0.147949 0.0387507 -0.039724 0.137901 0.0465004 -0.0401362 0.139594 0.0527196 -0.0402139 0.141395 0.0476786 -0.0402139 0.144922 0.0488679 -0.039724 0.143076 0.0540345 -0.039724 0.13194 0.0614072 -0.0401362 0.13275 0.0681421 -0.0402139 0.135283 0.0629632 -0.0402139 0.138657 0.0645337 -0.039724 0.136061 0.0698417 -0.039724 0.107047 0.103956 -0.0402139 0.104401 0.101387 -0.0401362 0.109717 0.106549 -0.039724 0.0969506 0.11343 -0.0402139 0.0937172 0.120862 -0.039724 0.0795041 0.126273 -0.0402139 0.0731054 0.130083 -0.0402139 0.0595143 0.136835 -0.0402139 0.0580436 0.133454 -0.0401362 0.0523595 0.13973 -0.0402139 0.0510656 0.136276 -0.0401362 0.0536655 0.143215 -0.039724 0.0297424 0.146223 -0.0402139 0.0219127 0.1476 -0.0402139 0.0139896 0.14856 -0.0402139 0.00600632 0.149097 -0.0402139 -0.00200283 0.149204 -0.0402139 -0.0179607 0.148133 -0.0402139 -0.0175169 0.144472 -0.0401362 -0.0258412 0.146963 -0.0402139 -0.0252026 0.143331 -0.0401362 -0.0264858 0.150629 -0.039724 -0.0487019 0.141046 -0.0402139 -0.0559647 0.138325 -0.0402139 -0.0698037 0.131884 -0.0402139 -0.0680786 0.128624 -0.0401362 -0.0715447 0.135173 -0.039724 -0.0825975 0.124272 -0.0402139 -0.094232 0.115699 -0.0402139 -0.0919032 0.11284 -0.0401362 -0.0995917 0.111119 -0.0402139 -0.0965824 0.118585 -0.039724 -0.10725 0.109032 -0.039724 -0.117911 0.0914492 -0.0402139 -0.114997 0.0891893 -0.0401362 -0.121719 0.0863159 -0.0402139 -0.120852 0.0937302 -0.039724 -0.122133 0.0791353 -0.0401362 -0.128447 0.0759424 -0.0402139 -0.125228 0.0811405 -0.0402139 -0.128352 0.0831643 -0.039724 -0.131651 0.0778366 -0.039724 -0.139857 0.0618918 -0.039724 -0.151364 0.0218924 -0.039724 -0.14826 0.0168781 -0.0402139 -0.148693 0.0124997 -0.0402139 -0.152883 0.00416085 -0.039724 -0.152707 0.00843162 -0.039724 -0.146291 0 -0.0402 -0.145476 -0.00395927 -0.0401362 -0.148991 -0.00822643 -0.0402139 -0.148693 -0.0124997 -0.0402139 -0.140996 -0.0160512 -0.0395028 -0.137879 -0.0115907 -0.0383714 -0.136258 -0.0240546 -0.0383714 -0.14496 -0.0353898 -0.0402139 -0.140523 -0.0501913 -0.0402139 -0.135182 -0.0538966 -0.0401362 -0.136453 -0.0603856 -0.0402139 -0.134049 -0.0655493 -0.0402139 -0.106672 -0.0989952 -0.0401362 -0.104016 -0.0965303 -0.0395028 -0.102054 -0.103749 -0.0401362 -0.109375 -0.101504 -0.0402139 -0.0919032 -0.11284 -0.0401362 -0.0896149 -0.11003 -0.0395028 -0.094232 -0.115699 -0.0402139 -0.0805563 -0.121201 -0.0401362 -0.0744529 -0.125043 -0.0401362 -0.0614487 -0.13192 -0.0401362 -0.0599187 -0.128636 -0.0395028 -0.0630058 -0.135263 -0.0402139 -0.0402229 -0.139861 -0.0401362 -0.0327814 -0.14179 -0.0401362 -0.0252026 -0.143331 -0.0401362 -0.0175169 -0.144472 -0.0401362 -0.00195333 -0.145517 -0.0401362 -0.0019047 -0.141894 -0.0395028 0.00585789 -0.145412 -0.0401362 0.00571204 -0.141791 -0.0395028 0.0136438 -0.144889 -0.0401362 0.0133041 -0.141281 -0.0395028 0.0139896 -0.14856 -0.0402139 0.0365212 -0.140873 -0.0401362 0.0438831 -0.138756 -0.0401362 0.0510656 -0.136276 -0.0401362 0.0647945 -0.13031 -0.0401362 0.0631812 -0.127065 -0.0395028 0.0664364 -0.133612 -0.0402139 0.0775393 -0.123153 -0.0401362 0.0891768 -0.115006 -0.0401362 0.0869564 -0.112143 -0.0395028 0.0945546 -0.110627 -0.0401362 0.0914365 -0.11792 -0.0402139 0.104401 -0.101387 -0.0401362 0.101802 -0.0988627 -0.0395028 0.108867 -0.0965765 -0.0401362 0.107047 -0.103956 -0.0402139 0.113028 -0.0916707 -0.0401362 0.110214 -0.0893882 -0.0395028 0.11689 -0.0866925 -0.0401362 0.115893 -0.0939936 -0.0402139 0.120458 -0.0816629 -0.0401362 0.117459 -0.0796296 -0.0395028 0.123738 -0.0766021 -0.0401362 0.12351 -0.0837322 -0.0402139 0.126739 -0.0715282 -0.0401362 0.123583 -0.0697472 -0.0395028 0.129469 -0.0664581 -0.0401362 0.12995 -0.0733406 -0.0402139 0.13275 -0.0681421 -0.0402139 0.134161 -0.0563893 -0.0401362 0.130821 -0.0549853 -0.0395028 0.136144 -0.0514167 -0.0401362 0.137561 -0.0578182 -0.0402139 0.139594 -0.0527196 -0.0402139 0.141395 -0.0476786 -0.0402139 0.142976 -0.0427052 -0.0402139 0.144348 -0.0378077 -0.0402139 0.145524 -0.0329935 -0.0402139 0.146515 -0.0282686 -0.0402139 0.147333 -0.0236381 -0.0402139 0.147989 -0.0191061 -0.0402139 0.148494 -0.0146759 -0.0402139 0.148858 -0.0103498 -0.0402139 0.149092 -0.00612964 -0.0402139 0.149204 -0.00201636 -0.0402139 0.149204 0.00201636 -0.0402139 0.149092 0.00612964 -0.0402139 0.148858 0.0103498 -0.0402139 0.148494 0.0146759 -0.0402139 0.147989 0.0191061 -0.0402139 0.147333 0.0236381 -0.0402139 0.144348 0.0378077 -0.0402139 0.142976 0.0427052 -0.0402139 0.137561 0.0578182 -0.0402139 0.123738 0.0766021 -0.0401362 0.120657 0.0746948 -0.0395028 0.120458 0.0816629 -0.0401362 0.126873 0.0785431 -0.0402139 0.119852 0.0888891 -0.0402139 0.113028 0.0916707 -0.0401362 0.111625 0.0990236 -0.0402139 0.0996304 0.106079 -0.0401362 0.0891768 0.115006 -0.0401362 0.0869564 0.112143 -0.0395028 0.0835023 0.11919 -0.0401362 0.0914365 0.11792 -0.0402139 0.0775393 0.123153 -0.0401362 0.0647945 0.13031 -0.0401362 0.0631812 0.127065 -0.0395028 0.0664364 0.133612 -0.0402139 0.0438831 0.138756 -0.0401362 0.0365212 0.140873 -0.0401362 0.0290073 0.14261 -0.0401362 0.0213712 0.143952 -0.0401362 0.0136438 0.144889 -0.0401362 -0.00195333 0.145517 -0.0401362 -0.0019047 0.141894 -0.0395028 -0.00975612 0.145203 -0.0401362 -0.00951321 0.141587 -0.0395028 -0.0100033 0.148882 -0.0402139 -0.0327814 0.14179 -0.0401362 -0.0402229 0.139861 -0.0401362 -0.0474984 0.13756 -0.0401362 -0.0614487 0.13192 -0.0401362 -0.0599187 0.128636 -0.0395028 -0.0630058 0.135263 -0.0402139 -0.0744529 0.125043 -0.0401362 -0.0805563 0.121201 -0.0401362 -0.0885649 0.120092 -0.0402139 -0.0971305 0.108373 -0.0401362 -0.10464 0.106378 -0.0402139 -0.106672 0.0989952 -0.0401362 -0.113798 0.0965193 -0.0402139 -0.130736 0.0639294 -0.0401362 -0.127481 0.0623376 -0.0395028 -0.133081 0.0588934 -0.0401362 -0.134049 0.0655493 -0.0402139 -0.136453 0.0603856 -0.0402139 -0.130303 0.046541 -0.0383714 -0.140523 0.0501913 -0.0402139 -0.142212 0.0451829 -0.0402139 -0.140445 0.0203131 -0.0395028 -0.13694 0.0198062 -0.0383714 -0.13705 0.0489509 -0.0401362 -0.138698 0.0440663 -0.0401362 -0.147681 0.0213596 -0.0402139 -0.143314 0.0253002 -0.0401362 -0.149162 0.00405959 -0.0402139 -0.148991 0.00822643 -0.0402139 -0.143251 0 -0.0398015 -0.141854 -0.00386068 -0.0395028 -0.145309 -0.00802313 -0.0401362 -0.145018 -0.0121908 -0.0401362 -0.144596 -0.016461 -0.0401362 -0.144031 -0.0208317 -0.0401362 -0.141378 -0.0345152 -0.0401362 -0.13187 -0.0418969 -0.0383714 -0.135245 -0.0429691 -0.0395028 -0.133237 -0.0373195 -0.0383714 -0.138698 -0.0440663 -0.0401362 -0.13705 -0.0489509 -0.0401362 -0.126529 -0.055994 -0.0383714 -0.129767 -0.057427 -0.0395028 -0.128527 -0.0512433 -0.0383714 -0.133081 -0.0588934 -0.0401362 -0.130736 -0.0639294 -0.0401362 -0.124947 -0.0672739 -0.0395028 -0.125273 -0.0740657 -0.0401362 -0.119092 -0.0771649 -0.0395028 -0.118711 -0.0841828 -0.0401362 -0.112133 -0.0869686 -0.0395028 -0.110985 -0.094134 -0.0401362 -0.099513 -0.101166 -0.0395028 -0.0971305 -0.108373 -0.0401362 -0.0842256 -0.114208 -0.0395028 -0.0785505 -0.118183 -0.0395028 -0.064727 -0.122292 -0.0383714 -0.0663835 -0.125422 -0.0395028 -0.0707875 -0.118887 -0.0383714 -0.0680786 -0.128624 -0.0401362 -0.0532226 -0.131548 -0.0395028 -0.0463157 -0.134135 -0.0395028 -0.0392214 -0.136379 -0.0395028 -0.0319652 -0.138259 -0.0395028 -0.0166545 -0.137359 -0.0383714 -0.0170807 -0.140875 -0.0395028 -0.0239619 -0.136275 -0.0383714 -0.00927582 -0.138054 -0.0383714 -0.00951321 -0.141587 -0.0395028 -0.00975612 -0.145203 -0.0401362 0.020839 -0.140368 -0.0395028 0.0282851 -0.139059 -0.0395028 0.0356118 -0.137365 -0.0395028 0.0485516 -0.129567 -0.0383714 0.0497941 -0.132883 -0.0395028 0.0417227 -0.131925 -0.0383714 0.055186 -0.126884 -0.0383714 0.0565984 -0.130131 -0.0395028 0.0580436 -0.133454 -0.0401362 0.0695235 -0.123709 -0.0395028 0.0793914 -0.113322 -0.0383714 0.0814232 -0.116223 -0.0395028 0.073722 -0.11709 -0.0383714 0.0835023 -0.11919 -0.0401362 0.0922003 -0.107873 -0.0395028 0.0996304 -0.106079 -0.0401362 0.13194 -0.0614072 -0.0401362 0.137901 -0.0465004 -0.0401362 0.139443 -0.0416498 -0.0401362 0.140781 -0.0368734 -0.0401362 0.141928 -0.0321781 -0.0401362 0.142895 -0.02757 -0.0401362 0.143692 -0.0230539 -0.0401362 0.144332 -0.018634 -0.0401362 0.144824 -0.0143132 -0.0401362 0.145179 -0.0100941 -0.0401362 0.145407 -0.00597816 -0.0401362 0.145517 -0.00196653 -0.0401362 0.145517 0.00196653 -0.0401362 0.145407 0.00597816 -0.0401362 0.145179 0.0100941 -0.0401362 0.144824 0.0143132 -0.0401362 0.144332 0.018634 -0.0401362 0.143692 0.0230539 -0.0401362 0.121685 0.0410323 -0.0325813 0.124704 0.0420502 -0.0348514 0.123045 0.0367521 -0.0325813 0.141928 0.0321781 -0.0401362 0.140781 0.0368734 -0.0401362 0.139443 0.0416498 -0.0401362 0.126223 0.0476698 -0.0368012 0.124384 0.0522801 -0.0368012 0.127556 0.0536132 -0.0383714 0.136144 0.0514167 -0.0401362 0.134161 0.0563893 -0.0401362 0.123095 0.0631863 -0.0383714 0.126246 0.0648034 -0.0395028 0.125444 0.0583841 -0.0383714 0.129469 0.0664581 -0.0401362 0.126739 0.0715282 -0.0401362 0.111136 0.0824245 -0.0383714 0.11398 0.0845339 -0.0395028 0.114528 0.0776426 -0.0383714 0.11689 0.0866925 -0.0401362 0.103507 0.0918219 -0.0383714 0.106156 0.0941718 -0.0395028 0.107464 0.0871577 -0.0383714 0.108867 0.0965765 -0.0401362 0.101802 0.0988627 -0.0395028 0.0898996 0.105181 -0.0383714 0.0922003 0.107873 -0.0395028 0.0947255 0.100857 -0.0383714 0.0945546 0.110627 -0.0401362 0.0814232 0.116223 -0.0395028 0.0677886 0.120622 -0.0383714 0.0695235 0.123709 -0.0395028 0.073722 0.11709 -0.0383714 0.0712987 0.126868 -0.0401362 0.0565984 0.130131 -0.0395028 0.0497941 0.132883 -0.0395028 0.0427904 0.135301 -0.0395028 0.0356118 0.137365 -0.0395028 0.020319 0.136865 -0.0383714 0.020839 0.140368 -0.0395028 0.0275793 0.135589 -0.0383714 0.0129721 0.137756 -0.0383714 0.0133041 0.141281 -0.0395028 0.0055695 0.138253 -0.0383714 0.00571204 0.141791 -0.0395028 0.00585789 0.145412 -0.0401362 -0.0170807 0.140875 -0.0395028 -0.0245751 0.139762 -0.0395028 -0.0319652 0.138259 -0.0395028 -0.0392214 0.136379 -0.0395028 -0.0518945 0.128265 -0.0383714 -0.0532226 0.131548 -0.0395028 -0.04516 0.130788 -0.0383714 -0.0545816 0.134907 -0.0401362 -0.0663835 0.125422 -0.0395028 -0.0725991 0.121929 -0.0395028 -0.0821238 0.111358 -0.0383714 -0.0842256 0.114208 -0.0395028 -0.0765904 0.115234 -0.0383714 -0.0863762 0.117124 -0.0401362 -0.0896149 0.11003 -0.0395028 -0.0970298 0.0986418 -0.0383714 -0.099513 0.101166 -0.0395028 -0.0923487 0.103037 -0.0383714 -0.102054 0.103749 -0.0401362 -0.104016 0.0965303 -0.0395028 -0.110985 0.094134 -0.0401362 -0.112133 0.0869686 -0.0395028 -0.118711 0.0841828 -0.0401362 -0.119092 0.0771649 -0.0395028 -0.125273 0.0740657 -0.0401362 -0.128137 0.0689917 -0.0401362 -0.135182 0.0538966 -0.0401362 -0.140137 0.0392519 -0.0401362 -0.133638 0.0477321 -0.0395028 -0.142433 0.0298628 -0.0401362 -0.144031 0.0208317 -0.0401362 -0.144596 0.016461 -0.0401362 -0.145018 0.0121908 -0.0401362 -0.140996 0.0160512 -0.0395028 -0.141408 0.0118873 -0.0395028 -0.145476 0.00395927 -0.0401362 -0.145309 0.00802313 -0.0401362 -0.14028 0 -0.039046 -0.141691 -0.00782337 -0.0395028 -0.141408 -0.0118873 -0.0395028 -0.138887 -0.0291193 -0.0395028 -0.137858 -0.0336558 -0.0395028 -0.136647 -0.0382746 -0.0395028 -0.133638 -0.0477321 -0.0395028 -0.131816 -0.0525547 -0.0395028 -0.127481 -0.0623376 -0.0395028 -0.118799 -0.0639641 -0.0368012 -0.116144 -0.0686683 -0.0368012 -0.119105 -0.0704193 -0.0383714 -0.122154 -0.0722215 -0.0395028 -0.113233 -0.0733684 -0.0368012 -0.11006 -0.0780482 -0.0368012 -0.112866 -0.0800384 -0.0383714 -0.115755 -0.0820868 -0.0395028 -0.106617 -0.0826898 -0.0368012 -0.102897 -0.0872742 -0.0368012 -0.105521 -0.0894997 -0.0383714 -0.108222 -0.0917902 -0.0395028 -0.10142 -0.0941215 -0.0383714 -0.094617 -0.0961889 -0.0368012 -0.0900523 -0.100475 -0.0368012 -0.0923487 -0.103037 -0.0383714 -0.0947121 -0.105674 -0.0395028 -0.0873787 -0.107284 -0.0383714 -0.0800817 -0.108589 -0.0368012 -0.0746859 -0.112369 -0.0368012 -0.0765904 -0.115234 -0.0383714 -0.0690273 -0.115931 -0.0368012 -0.0725991 -0.121929 -0.0395028 -0.0584236 -0.125426 -0.0383714 -0.0518945 -0.128265 -0.0383714 -0.044037 -0.127536 -0.0368012 -0.0372917 -0.129669 -0.0368012 -0.0382427 -0.132975 -0.0383714 -0.0303926 -0.131457 -0.0368012 -0.0311676 -0.134809 -0.0383714 -0.023366 -0.132886 -0.0368012 -0.0245751 -0.139762 -0.0395028 -0.00185717 -0.138353 -0.0383714 0.0055695 -0.138253 -0.0383714 0.0129721 -0.137756 -0.0383714 0.020319 -0.136865 -0.0383714 0.0268935 -0.132217 -0.0368012 0.0338598 -0.130607 -0.0368012 0.0347232 -0.133938 -0.0383714 0.0406852 -0.128644 -0.0368012 0.0427904 -0.135301 -0.0395028 0.0616047 -0.123894 -0.0383714 0.066103 -0.117623 -0.0368012 0.0718888 -0.114178 -0.0368012 0.0756087 -0.120086 -0.0395028 0.0847866 -0.109344 -0.0383714 0.09237 -0.0983487 -0.0368012 0.0947255 -0.100857 -0.0383714 0.0876642 -0.102565 -0.0368012 0.0971497 -0.103438 -0.0395028 0.0967932 -0.0939988 -0.0368012 0.100933 -0.0895387 -0.0368012 0.103507 -0.0918219 -0.0383714 0.106156 -0.0941718 -0.0395028 0.107464 -0.0871577 -0.0383714 0.11398 -0.0845339 -0.0395028 0.114528 -0.0776426 -0.0383714 0.111136 -0.0824245 -0.0383714 0.120657 -0.0746948 -0.0395028 0.117503 -0.0663157 -0.0368012 0.120034 -0.0616151 -0.0368012 0.123095 -0.0631863 -0.0383714 0.126246 -0.0648034 -0.0395028 0.128655 -0.0598783 -0.0395028 0.127852 -0.0431118 -0.0368012 0.123115 -0.0464961 -0.0348514 0.124704 -0.0420502 -0.0348514 0.132755 -0.0501365 -0.0395028 0.134467 -0.0453426 -0.0395028 0.135971 -0.0406128 -0.0395028 0.137276 -0.0359553 -0.0395028 0.138394 -0.0313769 -0.0395028 0.139337 -0.0268835 -0.0395028 0.140115 -0.0224799 -0.0395028 0.140738 -0.01817 -0.0395028 0.141218 -0.0139569 -0.0395028 0.141565 -0.00984275 -0.0395028 0.141787 -0.00582931 -0.0395028 0.141893 -0.00191757 -0.0395028 0.141893 0.00191757 -0.0395028 0.141787 0.00582931 -0.0395028 0.141565 0.00984275 -0.0395028 0.141218 0.0139569 -0.0395028 0.140738 0.01817 -0.0395028 0.140115 0.0224799 -0.0395028 0.139337 0.0268835 -0.0395028 0.138394 0.0313769 -0.0395028 0.137276 0.0359553 -0.0395028 0.135971 0.0406128 -0.0395028 0.134467 0.0453426 -0.0395028 0.132755 0.0501365 -0.0395028 0.130821 0.0549853 -0.0395028 0.128655 0.0598783 -0.0395028 0.123583 0.0697472 -0.0395028 0.117646 0.0728309 -0.0383714 0.120499 0.0680068 -0.0383714 0.117459 0.0796296 -0.0395028 0.110214 0.0893882 -0.0395028 0.0967932 0.0939988 -0.0368012 0.09237 0.0983487 -0.0368012 0.0971497 0.103438 -0.0395028 0.0847866 0.109344 -0.0383714 0.0774173 0.110505 -0.0368012 0.0718888 0.114178 -0.0368012 0.0756087 0.120086 -0.0395028 0.0616047 0.123894 -0.0383714 0.055186 0.126884 -0.0383714 0.0473443 0.126346 -0.0368012 0.0406852 0.128644 -0.0368012 0.0417227 0.131925 -0.0383714 0.0338598 0.130607 -0.0368012 0.0347232 0.133938 -0.0383714 0.0268935 0.132217 -0.0368012 0.0282851 0.139059 -0.0395028 -0.00185717 0.138353 -0.0383714 -0.00927582 0.138054 -0.0383714 -0.0166545 0.137359 -0.0383714 -0.0239619 0.136275 -0.0383714 -0.0303926 0.131457 -0.0368012 -0.0372917 0.129669 -0.0368012 -0.0382427 0.132975 -0.0383714 -0.044037 0.127536 -0.0368012 -0.0463157 0.134135 -0.0395028 -0.0584236 0.125426 -0.0383714 -0.064727 0.122292 -0.0383714 -0.0690273 0.115931 -0.0368012 -0.0746859 0.112369 -0.0368012 -0.0785505 0.118183 -0.0395028 -0.085206 0.104617 -0.0368012 -0.0900523 0.100475 -0.0368012 -0.0947121 0.105674 -0.0395028 -0.0988985 0.0917811 -0.0368012 -0.102897 0.0872742 -0.0368012 -0.105521 0.0894997 -0.0383714 -0.108222 0.0917902 -0.0395028 -0.106617 0.0826898 -0.0368012 -0.11006 0.0780482 -0.0368012 -0.112866 0.0800384 -0.0383714 -0.115755 0.0820868 -0.0395028 -0.113284 0.0669775 -0.0348514 -0.115874 0.0623891 -0.0348514 -0.118799 0.0639641 -0.0368012 -0.122154 0.0722215 -0.0395028 -0.124947 0.0672739 -0.0395028 -0.121209 0.0592707 -0.0368012 -0.123383 0.0546016 -0.0368012 -0.126529 0.055994 -0.0383714 -0.129767 0.057427 -0.0395028 -0.131816 0.0525547 -0.0395028 -0.137858 0.0336558 -0.0395028 -0.137477 0.0156507 -0.0383714 -0.137879 0.0115907 -0.0383714 -0.141691 0.00782337 -0.0395028 -0.141854 0.00386068 -0.0395028 -0.124739 0 -0.0294625 -0.122537 0 -0.0273282 -0.122481 -0.00333343 -0.0273172 -0.138155 -0.00762815 -0.0383714 -0.125339 -0.00341122 -0.0300502 -0.128369 -0.00349369 -0.0325813 -0.127046 0 -0.0314829 -0.127094 -0.0183821 -0.0325813 -0.135421 -0.0283927 -0.0383714 -0.134418 -0.032816 -0.0383714 -0.122245 -0.0487387 -0.0348514 -0.120934 -0.0431947 -0.0325813 -0.119285 -0.0475588 -0.0325813 -0.130303 -0.046541 -0.0383714 -0.115874 -0.0623891 -0.0348514 -0.115363 -0.0564118 -0.0325813 -0.113069 -0.0608788 -0.0325813 -0.1243 -0.0607821 -0.0383714 -0.121829 -0.0655952 -0.0383714 -0.116121 -0.0752393 -0.0383714 -0.109335 -0.0847984 -0.0383714 -0.0964634 -0.0895212 -0.0348514 -0.0922873 -0.0938205 -0.0348514 -0.0970298 -0.0986418 -0.0383714 -0.083108 -0.102041 -0.0348514 -0.0781099 -0.105915 -0.0348514 -0.0821238 -0.111358 -0.0383714 -0.0631175 -0.119251 -0.0368012 -0.055568 -0.119296 -0.0348514 -0.0493581 -0.121996 -0.0348514 -0.0506041 -0.125076 -0.0368012 -0.0429527 -0.124396 -0.0348514 -0.04516 -0.130788 -0.0383714 -0.0162404 -0.133944 -0.0368012 -0.00904517 -0.134621 -0.0368012 -0.00181099 -0.134913 -0.0368012 0.00529728 -0.131496 -0.0348514 0.0123381 -0.131023 -0.0348514 0.0126496 -0.13433 -0.0368012 0.0193259 -0.130176 -0.0348514 0.0198138 -0.133462 -0.0368012 0.0262313 -0.128962 -0.0348514 0.0275793 -0.135589 -0.0383714 0.0473443 -0.126346 -0.0368012 0.0538138 -0.123729 -0.0368012 0.0585936 -0.117839 -0.0348514 0.0644754 -0.114726 -0.0348514 0.0677886 -0.120622 -0.0383714 0.0774173 -0.110505 -0.0368012 0.0806425 -0.104 -0.0348514 0.0855057 -0.10004 -0.0348514 0.0898996 -0.105181 -0.0383714 0.0992614 -0.0963958 -0.0383714 0.102212 -0.0828977 -0.0348514 0.105704 -0.0783959 -0.0348514 0.108372 -0.0803749 -0.0368012 0.10893 -0.0738477 -0.0348514 0.111896 -0.0692712 -0.0348514 0.114721 -0.0710199 -0.0368012 0.117646 -0.0728309 -0.0383714 0.120499 -0.0680068 -0.0383714 0.125444 -0.0583841 -0.0383714 0.127556 -0.0536132 -0.0383714 0.129442 -0.0488854 -0.0383714 0.131112 -0.0442111 -0.0383714 0.132578 -0.0395994 -0.0383714 0.13385 -0.0350581 -0.0383714 0.134941 -0.030594 -0.0383714 0.13586 -0.0262127 -0.0383714 0.137226 -0.0177166 -0.0383714 0.137695 -0.0136086 -0.0383714 0.138032 -0.00959713 -0.0383714 0.138249 -0.00568385 -0.0383714 0.138353 -0.00186972 -0.0383714 0.138353 0.00186972 -0.0383714 0.138249 0.00568385 -0.0383714 0.138032 0.00959713 -0.0383714 0.137695 0.0136086 -0.0383714 0.137226 0.0177166 -0.0383714 0.136618 0.021919 -0.0383714 0.13586 0.0262127 -0.0383714 0.134941 0.030594 -0.0383714 0.13385 0.0350581 -0.0383714 0.132578 0.0395994 -0.0383714 0.131112 0.0442111 -0.0383714 0.129442 0.0488854 -0.0383714 0.117079 0.060098 -0.0348514 0.11461 0.0646828 -0.0348514 0.117503 0.0663157 -0.0368012 0.111896 0.0692712 -0.0348514 0.10893 0.0738477 -0.0348514 0.11168 0.0757119 -0.0368012 0.105704 0.0783959 -0.0348514 0.102212 0.0828977 -0.0348514 0.104792 0.0849904 -0.0368012 0.100933 0.0895387 -0.0368012 0.0992614 0.0963958 -0.0383714 0.0876642 0.102565 -0.0368012 0.0806425 0.104 -0.0348514 0.0755111 0.107784 -0.0348514 0.0793914 0.113322 -0.0383714 0.066103 0.117623 -0.0368012 0.0585936 0.117839 -0.0348514 0.0524887 0.120682 -0.0348514 0.0538138 0.123729 -0.0368012 0.0461785 0.123235 -0.0348514 0.0485516 0.129567 -0.0383714 0.0198138 0.133462 -0.0368012 0.0126496 0.13433 -0.0368012 0.00543101 0.134815 -0.0368012 -0.00181099 0.134913 -0.0368012 -0.00882245 0.131306 -0.0348514 -0.0158405 0.130646 -0.0348514 -0.0162404 0.133944 -0.0368012 -0.0227907 0.129614 -0.0348514 -0.023366 0.132886 -0.0368012 -0.0296442 0.12822 -0.0348514 -0.0311676 0.134809 -0.0383714 -0.0506041 0.125076 -0.0368012 -0.055568 0.119296 -0.0348514 -0.0615634 0.116315 -0.0348514 -0.0631175 0.119251 -0.0368012 -0.0673277 0.113076 -0.0348514 -0.0707875 0.118887 -0.0383714 -0.0781099 0.105915 -0.0348514 -0.083108 0.102041 -0.0348514 -0.0873787 0.107284 -0.0383714 -0.0922873 0.0938205 -0.0348514 -0.0964634 0.0895212 -0.0348514 -0.10142 0.0941215 -0.0383714 -0.109335 0.0847984 -0.0383714 -0.116121 0.0752393 -0.0383714 -0.119105 0.0704193 -0.0383714 -0.121829 0.0655952 -0.0383714 -0.1243 0.0607821 -0.0383714 -0.128527 0.0512433 -0.0383714 -0.124753 0.0304565 -0.0325813 -0.125684 0.0263512 -0.0325813 -0.128802 0.0270049 -0.0348514 -0.133237 0.0373195 -0.0383714 -0.130247 0.0188381 -0.0348514 -0.133535 0.0193137 -0.0368012 -0.129599 0.0228789 -0.0348514 -0.134059 0.0152615 -0.0368012 -0.13445 0.0113025 -0.0368012 -0.138314 0.00376435 -0.0383714 -0.138155 0.00762815 -0.0383714 -0.131554 -0.00358036 -0.0348514 -0.13472 -0.00743846 -0.0368012 -0.13445 -0.0113025 -0.0368012 -0.13287 -0.0234565 -0.0368012 -0.132054 -0.0276866 -0.0368012 -0.131075 -0.032 -0.0368012 -0.129924 -0.0363915 -0.0368012 -0.128591 -0.0408551 -0.0368012 -0.127063 -0.0453837 -0.0368012 -0.125331 -0.049969 -0.0368012 -0.123383 -0.0546016 -0.0368012 -0.121209 -0.0592707 -0.0368012 -0.110542 -0.0653561 -0.0325813 -0.107771 -0.0698296 -0.0325813 -0.110445 -0.0715619 -0.0348514 -0.104751 -0.0742836 -0.0325813 -0.101474 -0.0787013 -0.0325813 -0.103991 -0.0806538 -0.0348514 -0.100364 -0.0851253 -0.0348514 -0.0988985 -0.0917811 -0.0368012 -0.0857087 -0.0956289 -0.0325813 -0.0810961 -0.0995705 -0.0325813 -0.085206 -0.104617 -0.0368012 -0.0728469 -0.109602 -0.0348514 -0.0656978 -0.110339 -0.0325813 -0.0600731 -0.113499 -0.0325813 -0.0615634 -0.116315 -0.0348514 -0.0542229 -0.116408 -0.0325813 -0.0569708 -0.122307 -0.0368012 -0.0363735 -0.126476 -0.0348514 -0.0296442 -0.12822 -0.0348514 -0.0227907 -0.129614 -0.0348514 -0.00860888 -0.128128 -0.0325813 -0.00882245 -0.131306 -0.0348514 -0.015457 -0.127483 -0.0325813 -0.00172364 -0.128405 -0.0325813 -0.0017664 -0.131591 -0.0348514 0.00516905 -0.128313 -0.0325813 0.00543101 -0.134815 -0.0368012 0.033026 -0.127391 -0.0348514 0.0396834 -0.125477 -0.0348514 0.0512181 -0.117761 -0.0325813 0.0524887 -0.120682 -0.0348514 0.0450607 -0.120251 -0.0325813 0.0571752 -0.114986 -0.0325813 0.0600728 -0.120814 -0.0368012 0.0701187 -0.111367 -0.0348514 0.0786903 -0.101482 -0.0325813 0.0736831 -0.105174 -0.0325813 0.0826783 -0.106625 -0.0368012 0.0879146 -0.0936049 -0.0325813 0.0921244 -0.0894648 -0.0325813 0.0944099 -0.0916843 -0.0348514 0.098448 -0.087334 -0.0348514 0.104792 -0.0849904 -0.0368012 0.11168 -0.0757119 -0.0368012 0.118385 -0.0497584 -0.0325813 0.113676 -0.0529071 -0.0300502 0.11559 -0.0485838 -0.0300502 0.122325 -0.0569323 -0.0368012 0.124384 -0.0522801 -0.0368012 0.126223 -0.0476698 -0.0368012 0.129281 -0.0386147 -0.0368012 0.130522 -0.0341863 -0.0368012 0.131585 -0.0298332 -0.0368012 0.130964 -0.0129434 -0.0348514 0.134271 -0.0132702 -0.0368012 0.130519 -0.0168507 -0.0348514 0.133814 -0.0172761 -0.0368012 0.1346 -0.00935849 -0.0368012 0.134811 -0.00554251 -0.0368012 0.134912 -0.00182322 -0.0368012 0.134912 0.00182322 -0.0368012 0.134811 0.00554251 -0.0368012 0.1346 0.00935849 -0.0368012 0.134271 0.0132702 -0.0368012 0.133814 0.0172761 -0.0368012 0.133221 0.0213739 -0.0368012 0.132481 0.0255609 -0.0368012 0.131585 0.0298332 -0.0368012 0.130522 0.0341863 -0.0368012 0.129281 0.0386147 -0.0368012 0.127852 0.0431118 -0.0368012 0.118385 0.0497584 -0.0325813 0.116425 0.0541862 -0.0325813 0.119313 0.0555305 -0.0348514 0.122325 0.0569323 -0.0368012 0.120034 0.0616151 -0.0368012 0.114721 0.0710199 -0.0368012 0.108372 0.0803749 -0.0368012 0.0921244 0.0894648 -0.0325813 0.0944099 0.0916843 -0.0348514 0.0960648 0.0852198 -0.0325813 0.0900956 0.0959271 -0.0348514 0.0786903 0.101482 -0.0325813 0.0834358 0.0976183 -0.0325813 0.0826783 0.106625 -0.0368012 0.0701187 0.111367 -0.0348514 0.0571752 0.114986 -0.0325813 0.0629146 0.111949 -0.0325813 0.0600728 0.120814 -0.0368012 0.0396834 0.125477 -0.0348514 0.033026 0.127391 -0.0348514 0.0262313 0.128962 -0.0348514 0.0120394 0.127851 -0.0325813 0.0123381 0.131023 -0.0348514 0.0188581 0.127025 -0.0325813 0.00516905 0.128313 -0.0325813 0.00529728 0.131496 -0.0348514 -0.00172364 0.128405 -0.0325813 -0.0017664 0.131591 -0.0348514 -0.00860888 0.128128 -0.0325813 -0.00904517 0.134621 -0.0368012 -0.0363735 0.126476 -0.0348514 -0.0429527 0.124396 -0.0348514 -0.0542229 0.116408 -0.0325813 -0.0481633 0.119043 -0.0325813 -0.0569708 0.122307 -0.0368012 -0.0710835 0.106949 -0.0325813 -0.0762191 0.103351 -0.0325813 -0.0800817 0.108589 -0.0368012 -0.087835 0.0980012 -0.0348514 -0.094617 0.0961889 -0.0368012 -0.0979343 0.0830646 -0.0325813 -0.101474 0.0787013 -0.0325813 -0.103991 0.0806538 -0.0348514 -0.104751 0.0742836 -0.0325813 -0.107771 0.0698296 -0.0325813 -0.110445 0.0715619 -0.0348514 -0.113233 0.0733684 -0.0368012 -0.116144 0.0686683 -0.0368012 -0.120934 0.0431947 -0.0325813 -0.11647 0.0464362 -0.0300502 -0.118079 0.042175 -0.0300502 -0.125331 0.049969 -0.0368012 -0.127063 0.0453837 -0.0368012 -0.128591 0.0408551 -0.0368012 -0.129924 0.0363915 -0.0368012 -0.131075 0.032 -0.0368012 -0.13114 0.0110242 -0.0348514 -0.134875 0.00367074 -0.0368012 -0.13472 0.00743846 -0.0368012 -0.129463 0 -0.0333707 -0.131402 -0.00725531 -0.0348514 -0.13114 -0.0110242 -0.0348514 -0.129599 -0.0228789 -0.0348514 -0.128802 -0.0270049 -0.0348514 -0.127848 -0.0312121 -0.0348514 -0.126725 -0.0354954 -0.0348514 -0.125424 -0.0398491 -0.0348514 -0.123934 -0.0442662 -0.0348514 -0.120345 -0.0532572 -0.0348514 -0.118225 -0.0578113 -0.0348514 -0.113284 -0.0669775 -0.0348514 -0.10735 -0.0761264 -0.0348514 -0.0956225 -0.0811038 -0.0300502 -0.0919063 -0.0852921 -0.0300502 -0.0941282 -0.0873541 -0.0325813 -0.0900532 -0.0915493 -0.0325813 -0.087835 -0.0980012 -0.0348514 -0.0762191 -0.103351 -0.0325813 -0.0694055 -0.104424 -0.0300502 -0.064147 -0.107734 -0.0300502 -0.0673277 -0.113076 -0.0348514 -0.0481633 -0.119043 -0.0325813 -0.0419129 -0.121384 -0.0325813 -0.0289266 -0.125116 -0.0325813 -0.0346551 -0.120501 -0.0300502 -0.0282438 -0.122163 -0.0300502 -0.022239 -0.126476 -0.0325813 -0.021714 -0.123491 -0.0300502 -0.0150922 -0.124474 -0.0300502 -0.0158405 -0.130646 -0.0348514 0.0120394 -0.127851 -0.0325813 0.0188581 -0.127025 -0.0325813 0.0255963 -0.12584 -0.0325813 0.0387228 -0.122439 -0.0325813 0.0314658 -0.121373 -0.0300502 0.0378087 -0.119549 -0.0300502 0.043997 -0.117413 -0.0300502 0.0461785 -0.123235 -0.0348514 0.0629146 -0.111949 -0.0325813 0.0668062 -0.106106 -0.0300502 0.0719438 -0.102692 -0.0300502 0.0755111 -0.107784 -0.0348514 0.0814662 -0.095314 -0.0300502 0.0858393 -0.0913953 -0.0300502 0.0900956 -0.0959271 -0.0348514 0.0937971 -0.0832082 -0.0300502 0.0973829 -0.0789815 -0.0300502 0.0997372 -0.080891 -0.0325813 0.10071 -0.0746923 -0.0300502 0.103784 -0.070359 -0.0300502 0.106293 -0.07206 -0.0325813 0.10661 -0.0659987 -0.0300502 0.109195 -0.0616271 -0.0300502 0.111835 -0.063117 -0.0325813 0.11461 -0.0646828 -0.0348514 0.117079 -0.060098 -0.0348514 0.119313 -0.0555305 -0.0348514 0.121322 -0.0509928 -0.0348514 0.119494 -0.0270918 -0.0273172 0.116891 -0.0265018 -0.0244418 0.120308 -0.0232121 -0.0273172 0.126098 -0.0376639 -0.0348514 0.127308 -0.0333446 -0.0348514 0.128345 -0.0290986 -0.0348514 0.129219 -0.0249315 -0.0348514 0.129941 -0.0208477 -0.0348514 0.131286 -0.00912806 -0.0348514 0.131491 -0.00540604 -0.0348514 0.131591 -0.00177833 -0.0348514 0.131591 0.00177833 -0.0348514 0.131491 0.00540604 -0.0348514 0.131286 0.00912806 -0.0348514 0.130964 0.0129434 -0.0348514 0.123802 0.0198628 -0.0300502 0.123115 0.0237537 -0.0300502 0.126091 0.024328 -0.0325813 0.130519 0.0168507 -0.0348514 0.129941 0.0208477 -0.0348514 0.129219 0.0249315 -0.0348514 0.128345 0.0290986 -0.0348514 0.127308 0.0333446 -0.0348514 0.126098 0.0376639 -0.0348514 0.123115 0.0464961 -0.0348514 0.121322 0.0509928 -0.0348514 0.109195 0.0616271 -0.0300502 0.10661 0.0659987 -0.0300502 0.109187 0.0675943 -0.0325813 0.103784 0.070359 -0.0300502 0.10071 0.0746923 -0.0300502 0.103145 0.0764981 -0.0325813 0.0973829 0.0789815 -0.0300502 0.0937971 0.0832082 -0.0300502 0.098448 0.087334 -0.0348514 0.0858393 0.0913953 -0.0300502 0.0814662 0.095314 -0.0300502 0.0855057 0.10004 -0.0348514 0.0736831 0.105174 -0.0325813 0.0668062 0.106106 -0.0300502 0.0614294 0.109307 -0.0300502 0.0644754 0.114726 -0.0348514 0.0512181 0.117761 -0.0325813 0.0450607 0.120251 -0.0325813 0.0322266 0.124307 -0.0325813 0.0378087 0.119549 -0.0300502 0.0314658 0.121373 -0.0300502 0.0255963 0.12584 -0.0325813 0.0249921 0.122869 -0.0300502 0.0184129 0.124026 -0.0300502 0.0193259 0.130176 -0.0348514 -0.015457 0.127483 -0.0325813 -0.022239 0.126476 -0.0325813 -0.0289266 0.125116 -0.0325813 -0.0419129 0.121384 -0.0325813 -0.0346551 0.120501 -0.0300502 -0.0409236 0.118519 -0.0300502 -0.0470263 0.116233 -0.0300502 -0.0493581 0.121996 -0.0348514 -0.0600731 0.113499 -0.0325813 -0.064147 0.107734 -0.0300502 -0.0694055 0.104424 -0.0300502 -0.0728469 0.109602 -0.0348514 -0.0810961 0.0995705 -0.0325813 -0.0836855 0.0933715 -0.0300502 -0.0879275 0.0893882 -0.0300502 -0.0900532 0.0915493 -0.0325813 -0.0941282 0.0873541 -0.0325813 -0.100364 0.0851253 -0.0348514 -0.10735 0.0761264 -0.0348514 -0.1104 0.0594417 -0.0300502 -0.11264 0.0550802 -0.0300502 -0.115363 0.0564118 -0.0325813 -0.118225 0.0578113 -0.0348514 -0.120345 0.0532572 -0.0348514 -0.122245 0.0487387 -0.0348514 -0.123934 0.0442662 -0.0348514 -0.125424 0.0398491 -0.0348514 -0.126725 0.0354954 -0.0348514 -0.127848 0.0312121 -0.0348514 -0.127965 0.0107573 -0.0325813 -0.131554 0.00358036 -0.0348514 -0.131402 0.00725531 -0.0348514 -0.128221 -0.00707967 -0.0325813 -0.119089 -0.0135572 -0.0244418 -0.121265 -0.0175389 -0.0273172 -0.126461 -0.0223251 -0.0325813 -0.125684 -0.0263512 -0.0325813 -0.124753 -0.0304565 -0.0325813 -0.123658 -0.0346362 -0.0325813 -0.122388 -0.0388845 -0.0325813 -0.105464 -0.0515712 -0.021483 -0.105533 -0.0568212 -0.0244418 -0.107674 -0.052652 -0.0244418 -0.117432 -0.051968 -0.0325813 -0.107932 -0.0638133 -0.0300502 -0.107883 -0.0580864 -0.0273172 -0.105471 -0.0623583 -0.0273172 -0.102278 -0.0725301 -0.0300502 -0.102828 -0.0666266 -0.0273172 -0.0999463 -0.0708763 -0.0273172 -0.0968195 -0.0750914 -0.0273172 -0.0934422 -0.0792545 -0.0273172 -0.0979343 -0.0830646 -0.0325813 -0.0836855 -0.0933715 -0.0300502 -0.0859226 -0.0873501 -0.0273172 -0.0817773 -0.0912425 -0.0273172 -0.0791818 -0.09722 -0.0300502 -0.072723 -0.0986108 -0.0273172 -0.067823 -0.102043 -0.0273172 -0.0710835 -0.106949 -0.0325813 -0.058655 -0.11082 -0.0300502 -0.0529429 -0.11366 -0.0300502 -0.0409236 -0.118519 -0.0300502 -0.045954 -0.113582 -0.0273172 -0.0399904 -0.115817 -0.0273172 -0.033865 -0.117753 -0.0273172 -0.035493 -0.123414 -0.0325813 -0.00840566 -0.125103 -0.0300502 -0.00168295 -0.125374 -0.0300502 0.00504703 -0.125284 -0.0300502 0.0184129 -0.124026 -0.0300502 0.0114872 -0.121987 -0.0273172 0.0179931 -0.121198 -0.0273172 0.0249921 -0.122869 -0.0300502 0.0244222 -0.120068 -0.0273172 0.0307484 -0.118605 -0.0273172 0.0322266 -0.124307 -0.0325813 0.0500091 -0.114981 -0.0300502 0.0558256 -0.112272 -0.0300502 0.0600287 -0.106814 -0.0273172 0.0652829 -0.103686 -0.0273172 0.0684213 -0.108671 -0.0325813 0.0768328 -0.0990869 -0.0300502 0.0834358 -0.0976183 -0.0325813 0.0878988 -0.0853612 -0.0273172 0.0916584 -0.0813109 -0.0273172 0.0960648 -0.0852198 -0.0325813 0.103145 -0.0764981 -0.0325813 0.109187 -0.0675943 -0.0325813 0.114245 -0.0586432 -0.0325813 0.116425 -0.0541862 -0.0325813 0.120135 -0.0453705 -0.0325813 0.121685 -0.0410323 -0.0325813 0.123045 -0.0367521 -0.0325813 0.124226 -0.0325374 -0.0325813 0.125238 -0.0283942 -0.0325813 0.126091 -0.024328 -0.0325813 0.126795 -0.020343 -0.0325813 0.12736 -0.0164428 -0.0325813 0.127794 -0.0126301 -0.0325813 0.128107 -0.00890709 -0.0325813 0.128308 -0.00527517 -0.0325813 0.128405 -0.00173528 -0.0325813 0.128405 0.00173528 -0.0325813 0.128308 0.00527517 -0.0325813 0.128107 0.00890709 -0.0325813 0.127794 0.0126301 -0.0325813 0.12736 0.0164428 -0.0325813 0.126795 0.020343 -0.0325813 0.125238 0.0283942 -0.0325813 0.124226 0.0325374 -0.0325813 0.104442 0.0536111 -0.021483 0.106435 0.0495366 -0.021483 0.104409 0.048594 -0.0185002 0.120135 0.0453705 -0.0325813 0.111084 0.0517008 -0.0273172 0.109004 0.0559533 -0.0273172 0.111548 0.0572589 -0.0300502 0.114245 0.0586432 -0.0325813 0.111835 0.063117 -0.0325813 0.106293 0.07206 -0.0325813 0.0997372 0.080891 -0.0325813 0.0878988 0.0853612 -0.0273172 0.0838821 0.0893114 -0.0273172 0.0879146 0.0936049 -0.0325813 0.0768328 0.0990869 -0.0300502 0.0703034 0.10035 -0.0273172 0.0652829 0.103686 -0.0273172 0.0684213 0.108671 -0.0325813 0.0558256 0.112272 -0.0300502 0.043997 0.117413 -0.0300502 0.0488688 0.112359 -0.0273172 0.0429938 0.114736 -0.0273172 0.0369466 0.116823 -0.0273172 0.0387228 0.122439 -0.0325813 0.0117552 0.124833 -0.0300502 0.00504703 0.125284 -0.0300502 -0.00168295 0.125374 -0.0300502 -0.00840566 0.125103 -0.0300502 -0.021714 0.123491 -0.0300502 -0.014748 0.121636 -0.0273172 -0.0212189 0.120675 -0.0273172 -0.0282438 0.122163 -0.0300502 -0.0275998 0.119377 -0.0273172 -0.033865 0.117753 -0.0273172 -0.035493 0.123414 -0.0325813 -0.0529429 0.11366 -0.0300502 -0.0573176 0.108293 -0.0273172 -0.0626843 0.105278 -0.0273172 -0.0656978 0.110339 -0.0325813 -0.0744199 0.100912 -0.0300502 -0.0773763 0.0950033 -0.0273172 -0.0817773 0.0912425 -0.0273172 -0.0857087 0.0956289 -0.0325813 -0.0956225 0.0811038 -0.0300502 -0.0898107 0.0833473 -0.0273172 -0.0934422 0.0792545 -0.0273172 -0.102278 0.0725301 -0.0300502 -0.0968195 0.0750914 -0.0273172 -0.0999463 0.0708763 -0.0273172 -0.107932 0.0638133 -0.0300502 -0.102828 0.0666266 -0.0273172 -0.105471 0.0623583 -0.0273172 -0.110542 0.0653561 -0.0325813 -0.113069 0.0608788 -0.0325813 -0.117432 0.051968 -0.0325813 -0.119285 0.0475588 -0.0325813 -0.122388 0.0388845 -0.0325813 -0.123658 0.0346362 -0.0325813 -0.124945 0.0105034 -0.0300502 -0.128221 0.00707967 -0.0325813 -0.128369 0.00349369 -0.0325813 -0.125195 -0.00691255 -0.0300502 -0.124094 -0.0179482 -0.0300502 -0.123476 -0.0217981 -0.0300502 -0.122717 -0.0257292 -0.0300502 -0.121808 -0.0297375 -0.0300502 -0.120739 -0.0338186 -0.0300502 -0.118079 -0.042175 -0.0300502 -0.11647 -0.0464362 -0.0300502 -0.11466 -0.0507412 -0.0300502 -0.11264 -0.0550802 -0.0300502 -0.1104 -0.0594417 -0.0300502 -0.105227 -0.0681812 -0.0300502 -0.0990786 -0.0768435 -0.0300502 -0.0878546 -0.081532 -0.0244418 -0.0898107 -0.0833473 -0.0273172 -0.0879275 -0.0893882 -0.0300502 -0.0756911 -0.0929341 -0.0244418 -0.0773763 -0.0950033 -0.0273172 -0.0744199 -0.100912 -0.0300502 -0.0626843 -0.105278 -0.0273172 -0.0560692 -0.105935 -0.0244418 -0.0517357 -0.111068 -0.0273172 -0.0573176 -0.108293 -0.0273172 -0.0506089 -0.108649 -0.0244418 -0.0470263 -0.116233 -0.0300502 -0.0275998 -0.119377 -0.0273172 -0.0212189 -0.120675 -0.0273172 -0.014748 -0.121636 -0.0273172 -0.0080351 -0.119588 -0.0244418 -0.00164458 -0.122515 -0.0273172 -0.008214 -0.122251 -0.0273172 -0.00160876 -0.119847 -0.0244418 0.00493195 -0.122427 -0.0273172 0.00482453 -0.119761 -0.0244418 0.0117552 -0.124833 -0.0300502 0.0369466 -0.116823 -0.0273172 0.0429938 -0.114736 -0.0273172 0.0478044 -0.109912 -0.0244418 0.0545527 -0.109712 -0.0273172 0.0488688 -0.112359 -0.0273172 0.0533645 -0.107323 -0.0244418 0.0614294 -0.109307 -0.0300502 0.0703034 -0.10035 -0.0273172 0.0734456 -0.0947187 -0.0244418 0.0796086 -0.0931407 -0.0273172 0.0750809 -0.0968276 -0.0273172 0.0838821 -0.0893114 -0.0273172 0.0899498 -0.0873529 -0.0300502 0.0930898 -0.0754996 -0.0244418 0.0984139 -0.0729892 -0.0273172 0.0951624 -0.0771806 -0.0273172 0.0992086 -0.0672572 -0.0244418 0.104179 -0.0644938 -0.0273172 0.101418 -0.0687547 -0.0273172 0.105875 -0.0399852 -0.0155526 0.102741 -0.043183 -0.0126994 0.104259 -0.039375 -0.0126994 0.111548 -0.0572589 -0.0300502 0.10844 -0.0323898 -0.0155526 0.109481 -0.0286753 -0.0155526 0.111406 -0.0291794 -0.0185002 0.117299 -0.0442995 -0.0300502 0.118812 -0.0400637 -0.0300502 0.120141 -0.0358846 -0.0300502 0.121294 -0.0317693 -0.0300502 0.122282 -0.027724 -0.0300502 0.123115 -0.0237537 -0.0300502 0.123802 -0.0198628 -0.0300502 0.124353 -0.0160546 -0.0300502 0.124777 -0.012332 -0.0300502 0.125083 -0.00869683 -0.0300502 0.12528 -0.00515065 -0.0300502 0.125374 -0.00169432 -0.0300502 0.125374 0.00169432 -0.0300502 0.12528 0.00515065 -0.0300502 0.125083 0.00869683 -0.0300502 0.124777 0.012332 -0.0300502 0.124353 0.0160546 -0.0300502 0.107736 0.0406881 -0.0185002 0.107241 0.0361619 -0.0155526 0.105875 0.0399852 -0.0155526 0.122282 0.027724 -0.0300502 0.121294 0.0317693 -0.0300502 0.120141 0.0358846 -0.0300502 0.118812 0.0400637 -0.0300502 0.117299 0.0442995 -0.0300502 0.11559 0.0485838 -0.0300502 0.113676 0.0529071 -0.0300502 0.10191 0.0630891 -0.0244418 0.101418 0.0687547 -0.0273172 0.104179 0.0644938 -0.0273172 0.0962705 0.0713995 -0.0244418 0.0951624 0.0771806 -0.0273172 0.0984139 0.0729892 -0.0273172 0.0916584 0.0813109 -0.0273172 0.0899498 0.0873529 -0.0300502 0.0796086 0.0931407 -0.0273172 0.0734456 0.0947187 -0.0244418 0.0750809 0.0968276 -0.0273172 0.0719438 0.102692 -0.0300502 0.0600287 0.106814 -0.0273172 0.0533645 0.107323 -0.0244418 0.0545527 0.109712 -0.0273172 0.0500091 0.114981 -0.0300502 0.0307484 0.118605 -0.0273172 0.0244222 0.120068 -0.0273172 0.0179931 0.121198 -0.0273172 0.011237 0.11933 -0.0244418 0.00493195 0.122427 -0.0273172 0.0114872 0.121987 -0.0273172 0.00482453 0.119761 -0.0244418 -0.00164458 0.122515 -0.0273172 -0.00160876 0.119847 -0.0244418 -0.008214 0.122251 -0.0273172 -0.0080351 0.119588 -0.0244418 -0.0150922 0.124474 -0.0300502 -0.0399904 0.115817 -0.0273172 -0.045954 0.113582 -0.0273172 -0.0506089 0.108649 -0.0244418 -0.0517357 0.111068 -0.0273172 -0.058655 0.11082 -0.0300502 -0.067823 0.102043 -0.0273172 -0.0711391 0.0964631 -0.0244418 -0.072723 0.0986108 -0.0273172 -0.0791818 0.09722 -0.0300502 -0.0840512 0.0854476 -0.0244418 -0.0859226 0.0873501 -0.0273172 -0.0919063 0.0852921 -0.0300502 -0.0990786 0.0768435 -0.0300502 -0.105227 0.0681812 -0.0300502 -0.107861 0.034269 -0.0155526 -0.104953 0.0374866 -0.0126994 -0.106215 0.033746 -0.0126994 -0.11466 0.0507412 -0.0300502 -0.115416 0.0323277 -0.0244418 -0.113047 0.0316641 -0.021483 -0.116438 0.0284266 -0.0244418 -0.119499 0.0379666 -0.0300502 -0.120739 0.0338186 -0.0300502 -0.121808 0.0297375 -0.0300502 -0.122717 0.0257292 -0.0300502 -0.120661 0.0213011 -0.0273172 -0.125339 0.00341122 -0.0300502 -0.125195 0.00691255 -0.0300502 -0.120436 0 -0.0250934 -0.12234 -0.00675494 -0.0273172 -0.120661 -0.0213011 -0.0273172 -0.119919 -0.0251425 -0.0273172 -0.119031 -0.0290595 -0.0273172 -0.114231 -0.0362928 -0.0244418 -0.115387 -0.0412134 -0.0273172 -0.113814 -0.0453774 -0.0273172 -0.112045 -0.0495842 -0.0273172 -0.110071 -0.0538242 -0.0273172 -0.0966491 -0.0626229 -0.0185002 -0.0957627 -0.0679095 -0.021483 -0.0985238 -0.0638376 -0.021483 -0.0910015 -0.0705791 -0.0185002 -0.0895308 -0.075937 -0.021483 -0.0927667 -0.0719481 -0.021483 -0.091407 -0.0775284 -0.0244418 -0.0799963 -0.0892552 -0.0244418 -0.0783542 -0.0874231 -0.021483 -0.0663458 -0.0998205 -0.0244418 -0.064984 -0.0977715 -0.021483 -0.0613191 -0.102985 -0.0244418 -0.0600604 -0.100871 -0.021483 -0.0449532 -0.111109 -0.0244418 -0.0331274 -0.115189 -0.0244418 -0.0324474 -0.112824 -0.021483 -0.0269987 -0.116777 -0.0244418 -0.0264445 -0.11438 -0.021483 -0.0207568 -0.118047 -0.0244418 -0.0203307 -0.115624 -0.021483 -0.0144268 -0.118986 -0.0244418 -0.0141307 -0.116544 -0.021483 0.011237 -0.11933 -0.0244418 0.0176012 -0.118558 -0.0244418 0.0300787 -0.116022 -0.0244418 0.0294613 -0.113641 -0.021483 0.0361419 -0.114279 -0.0244418 0.0354 -0.111933 -0.021483 0.0420574 -0.112237 -0.0244418 0.0411941 -0.109933 -0.021483 0.063861 -0.101428 -0.0244418 0.0625502 -0.0993462 -0.021483 0.0687722 -0.0981646 -0.0244418 0.0705692 -0.0910091 -0.0185002 0.0762763 -0.0892419 -0.021483 0.0719381 -0.0927745 -0.021483 0.0826169 -0.0802317 -0.0185002 0.0878216 -0.0779073 -0.021483 0.0842194 -0.081788 -0.021483 0.0896621 -0.07954 -0.0244418 0.106705 -0.0602219 -0.0273172 0.109004 -0.0559533 -0.0273172 0.111084 -0.0517008 -0.0273172 0.112955 -0.047476 -0.0273172 0.114624 -0.0432894 -0.0273172 0.116103 -0.0391502 -0.0273172 0.117401 -0.0350664 -0.0273172 0.118528 -0.0310449 -0.0273172 0.120979 -0.0194099 -0.0273172 0.121518 -0.0156886 -0.0273172 0.121932 -0.0120508 -0.0273172 0.122231 -0.00849853 -0.0273172 0.122423 -0.00503321 -0.0273172 0.122515 -0.00165569 -0.0273172 0.122515 0.00165569 -0.0273172 0.122423 0.00503321 -0.0273172 0.122231 0.00849853 -0.0273172 0.121932 0.0120508 -0.0273172 0.121518 0.0156886 -0.0273172 0.120979 0.0194099 -0.0273172 0.120308 0.0232121 -0.0273172 0.119494 0.0270918 -0.0273172 0.118528 0.0310449 -0.0273172 0.117401 0.0350664 -0.0273172 0.116103 0.0391502 -0.0273172 0.114624 0.0432894 -0.0273172 0.112955 0.047476 -0.0273172 0.0947586 0.0586619 -0.0126994 0.0922468 0.0625375 -0.0126994 0.0936764 0.0635068 -0.0155526 0.106705 0.0602219 -0.0273172 0.0826169 0.0802317 -0.0185002 0.0803708 0.0855729 -0.021483 0.0842194 0.081788 -0.021483 0.0820551 0.0873662 -0.0244418 0.0778748 0.0911121 -0.0244418 0.0705692 0.0910091 -0.0185002 0.0673605 0.0961496 -0.021483 0.0719381 0.0927745 -0.021483 0.063861 0.101428 -0.0244418 0.0625502 0.0993462 -0.021483 0.0587213 0.104488 -0.0244418 0.0512745 0.103119 -0.0185002 0.0468232 0.107656 -0.021483 0.0522691 0.10512 -0.021483 0.0478044 0.109912 -0.0244418 0.0361419 0.114279 -0.0244418 0.0354 0.111933 -0.021483 0.0300787 0.116022 -0.0244418 0.0294613 0.113641 -0.021483 0.0238903 0.117453 -0.0244418 0.0233999 0.115042 -0.021483 0.0176012 0.118558 -0.0244418 0.0172399 0.116125 -0.021483 -0.0144268 0.118986 -0.0244418 -0.0269987 0.116777 -0.0244418 -0.0264445 0.11438 -0.021483 -0.0331274 0.115189 -0.0244418 -0.0324474 0.112824 -0.021483 -0.0391195 0.113294 -0.0244418 -0.0383165 0.110969 -0.021483 -0.0449532 0.111109 -0.0244418 -0.0549184 0.10376 -0.021483 -0.0495701 0.106419 -0.021483 -0.0486269 0.104394 -0.0185002 -0.0560692 0.105935 -0.0244418 -0.0663458 0.0998205 -0.0244418 -0.064984 0.0977715 -0.021483 -0.0799963 0.0892552 -0.0244418 -0.0783542 0.0874231 -0.021483 -0.0910015 0.0705791 -0.0185002 -0.0957627 0.0679095 -0.021483 -0.0927667 0.0719481 -0.021483 -0.0966491 0.0626229 -0.0185002 -0.101056 0.059748 -0.021483 -0.0985238 0.0638376 -0.021483 -0.100118 0.0489572 -0.0126994 -0.101913 0.0451006 -0.0126994 -0.103493 0.0457995 -0.0155526 -0.107883 0.0580864 -0.0273172 -0.110071 0.0538242 -0.0273172 -0.112045 0.0495842 -0.0273172 -0.113814 0.0453774 -0.0273172 -0.115387 0.0412134 -0.0273172 -0.116774 0.0371009 -0.0273172 -0.117986 0.0330474 -0.0273172 -0.119031 0.0290595 -0.0273172 -0.119919 0.0251425 -0.0273172 -0.116985 0.00983423 -0.021483 -0.116644 0.013279 -0.021483 -0.122481 0.00333343 -0.0273172 -0.119676 -0.00660782 -0.0244418 -0.118623 -0.0171569 -0.0244418 -0.113047 -0.0316641 -0.021483 -0.114048 -0.0278431 -0.021483 -0.111878 -0.0273133 -0.0185002 -0.118033 -0.0208371 -0.0244418 -0.117307 -0.0245949 -0.0244418 -0.116438 -0.0284266 -0.0244418 -0.115416 -0.0323277 -0.0244418 -0.101913 -0.0451006 -0.0126994 -0.100118 -0.0489572 -0.0126994 -0.10167 -0.0497159 -0.0155526 -0.112874 -0.0403157 -0.0244418 -0.111335 -0.044389 -0.0244418 -0.109605 -0.0485043 -0.0244418 -0.103174 -0.0610002 -0.0244418 -0.100589 -0.0651754 -0.0244418 -0.0977695 -0.0693326 -0.0244418 -0.0947107 -0.0734559 -0.0244418 -0.0755354 -0.084278 -0.0155526 -0.0768633 -0.0857596 -0.0185002 -0.0793642 -0.0806827 -0.0155526 -0.0840512 -0.0854476 -0.0244418 -0.0696789 -0.094483 -0.021483 -0.068353 -0.0926852 -0.0185002 -0.0711391 -0.0964631 -0.0244418 -0.0495701 -0.106419 -0.021483 -0.0486269 -0.104394 -0.0185002 -0.0440305 -0.108828 -0.021483 -0.0431926 -0.106757 -0.0185002 -0.0383165 -0.110969 -0.021483 -0.0312801 -0.108766 -0.0155526 -0.03183 -0.110678 -0.0185002 -0.036938 -0.106976 -0.0155526 -0.0391195 -0.113294 -0.0244418 -0.00157574 -0.117387 -0.021483 -0.00154575 -0.115153 -0.0185002 0.0047255 -0.117302 -0.021483 0.00463558 -0.11507 -0.0185002 0.0110064 -0.11688 -0.021483 0.0107969 -0.114656 -0.0185002 0.0172399 -0.116125 -0.021483 0.0169119 -0.113915 -0.0185002 0.0233999 -0.115042 -0.021483 0.0229547 -0.112853 -0.0185002 0.0238903 -0.117453 -0.0244418 0.0522691 -0.10512 -0.021483 0.0512745 -0.103119 -0.0185002 0.057516 -0.102343 -0.021483 0.0564216 -0.100396 -0.0185002 0.0587213 -0.104488 -0.0244418 0.0774795 -0.0824943 -0.0155526 0.0788415 -0.0839446 -0.0185002 0.0735322 -0.0860314 -0.0155526 0.0778748 -0.0911121 -0.0244418 0.0820551 -0.0873662 -0.0244418 0.0859843 -0.083502 -0.0244418 0.0962272 -0.0595711 -0.0155526 0.0922468 -0.0625375 -0.0126994 0.0947586 -0.0586619 -0.0126994 0.0962705 -0.0713995 -0.0244418 0.100684 -0.0516824 -0.0155526 0.0970565 -0.0547763 -0.0126994 0.0991476 -0.0508937 -0.0126994 0.10191 -0.0630891 -0.0244418 0.104381 -0.0589103 -0.0244418 0.10663 -0.0547346 -0.0244418 0.108665 -0.0505747 -0.0244418 0.110495 -0.046442 -0.0244418 0.112128 -0.0423466 -0.0244418 0.113575 -0.0382975 -0.0244418 0.114844 -0.0343026 -0.0244418 0.115947 -0.0303688 -0.0244418 0.115915 -0.0185974 -0.021483 0.118871 -0.0153469 -0.0244418 0.118344 -0.0189871 -0.0244418 0.117687 -0.0227065 -0.0244418 0.119277 -0.0117883 -0.0244418 0.119569 -0.00831344 -0.0244418 0.119757 -0.00492358 -0.0244418 0.119847 -0.00161963 -0.0244418 0.119847 0.00161963 -0.0244418 0.119757 0.00492358 -0.0244418 0.119569 0.00831344 -0.0244418 0.119277 0.0117883 -0.0244418 0.118871 0.0153469 -0.0244418 0.118344 0.0189871 -0.0244418 0.117687 0.0227065 -0.0244418 0.116891 0.0265018 -0.0244418 0.115947 0.0303688 -0.0244418 0.114844 0.0343026 -0.0244418 0.113575 0.0382975 -0.0244418 0.112128 0.0423466 -0.0244418 0.110495 0.046442 -0.0244418 0.108665 0.0505747 -0.0244418 0.10663 0.0547346 -0.0244418 0.104381 0.0589103 -0.0244418 0.0878988 0.0712895 -0.0155526 0.0895148 0.0663891 -0.0126994 0.0865573 0.0702015 -0.0126994 0.0992086 0.0672572 -0.0244418 0.0846622 0.0751045 -0.0155526 0.0861505 0.0764248 -0.0185002 0.0930898 0.0754996 -0.0244418 0.0896621 0.07954 -0.0244418 0.0859843 0.083502 -0.0244418 0.0602999 0.0957721 -0.0155526 0.06136 0.0974558 -0.0185002 0.0649372 0.0926906 -0.0155526 0.0687722 0.0981646 -0.0244418 0.0459322 0.105607 -0.0185002 0.0411941 0.109933 -0.021483 0.0404102 0.107841 -0.0185002 0.0420574 0.112237 -0.0244418 0.0047255 0.117302 -0.021483 0.00463558 0.11507 -0.0185002 -0.00157574 0.117387 -0.021483 -0.00154575 0.115153 -0.0185002 -0.00787017 0.117133 -0.021483 -0.00772041 0.114905 -0.0185002 -0.0141307 0.116544 -0.021483 -0.0138618 0.114326 -0.0185002 -0.0203307 0.115624 -0.021483 -0.0199439 0.113424 -0.0185002 -0.0207568 0.118047 -0.0244418 -0.0538733 0.101786 -0.0185002 -0.0600604 0.100871 -0.021483 -0.0626461 0.0942542 -0.0155526 -0.0637474 0.0959111 -0.0185002 -0.0578997 0.097242 -0.0155526 -0.0613191 0.102985 -0.0244418 -0.0741374 0.0910265 -0.021483 -0.0727267 0.0892944 -0.0185002 -0.0756911 0.0929341 -0.0244418 -0.0863099 0.0732051 -0.0155526 -0.0878271 0.0744921 -0.0185002 -0.0829555 0.0769855 -0.0155526 -0.0878546 0.081532 -0.0244418 -0.091407 0.0775284 -0.0244418 -0.0947107 0.0734559 -0.0244418 -0.0977695 0.0693326 -0.0244418 -0.100589 0.0651754 -0.0244418 -0.103174 0.0610002 -0.0244418 -0.105533 0.0568212 -0.0244418 -0.107674 0.052652 -0.0244418 -0.109605 0.0485043 -0.0244418 -0.111335 0.044389 -0.0244418 -0.112874 0.0403157 -0.0244418 -0.114231 0.0362928 -0.0244418 -0.117307 0.0245949 -0.0244418 -0.119676 0.00660782 -0.0244418 -0.119813 0.00326083 -0.0244418 -0.116985 -0.00983423 -0.021483 -0.117219 -0.00647218 -0.021483 -0.116644 -0.013279 -0.021483 -0.116189 -0.0168048 -0.021483 -0.11561 -0.0204094 -0.021483 -0.114899 -0.02409 -0.021483 -0.111886 -0.0355479 -0.021483 -0.110557 -0.0394882 -0.021483 -0.10905 -0.0434779 -0.021483 -0.107355 -0.0475087 -0.021483 -0.0959339 -0.0567195 -0.0126994 -0.0974207 -0.0575986 -0.0155526 -0.0981274 -0.0528339 -0.0126994 -0.103367 -0.0556549 -0.021483 -0.101056 -0.059748 -0.021483 -0.078153 -0.0794514 -0.0126994 -0.0816895 -0.0758106 -0.0126994 -0.0860513 -0.0798584 -0.021483 -0.0823259 -0.0836937 -0.021483 -0.066147 -0.0896939 -0.0126994 -0.0671721 -0.091084 -0.0155526 -0.0703795 -0.0864126 -0.0126994 -0.0741374 -0.0910265 -0.021483 -0.0626461 -0.0942542 -0.0155526 -0.0578997 -0.097242 -0.0155526 -0.0589176 -0.0989515 -0.0185002 -0.0470575 -0.101025 -0.0126994 -0.0477868 -0.10259 -0.0155526 -0.0521346 -0.0985007 -0.0126994 -0.0549184 -0.10376 -0.021483 -0.0254931 -0.110266 -0.0155526 -0.0259413 -0.112204 -0.0185002 -0.0195993 -0.111464 -0.0155526 -0.0199439 -0.113424 -0.0185002 -0.0136223 -0.112351 -0.0155526 -0.0138618 -0.114326 -0.0185002 -0.00149586 -0.111437 -0.0126994 -0.00151905 -0.113164 -0.0155526 -0.00747125 -0.111196 -0.0126994 -0.00787017 -0.117133 -0.021483 0.0284014 -0.109552 -0.0155526 0.0341265 -0.107906 -0.0155526 0.0347264 -0.109803 -0.0185002 0.0397121 -0.105978 -0.0155526 0.0404102 -0.107841 -0.0185002 0.0496197 -0.0997913 -0.0126994 0.0503887 -0.101338 -0.0155526 0.0444498 -0.102199 -0.0126994 0.0468232 -0.107656 -0.021483 0.0602999 -0.0957721 -0.0155526 0.0649372 -0.0926906 -0.0155526 0.0660788 -0.09432 -0.0185002 0.0673605 -0.0961496 -0.021483 0.0803708 -0.0855729 -0.021483 0.0895148 -0.0663891 -0.0126994 0.0909021 -0.067418 -0.0155526 0.0865573 -0.0702015 -0.0126994 0.091179 -0.0739499 -0.021483 0.0942944 -0.0699339 -0.021483 0.0971723 -0.0658767 -0.021483 0.0998182 -0.0617941 -0.021483 0.102239 -0.0577011 -0.021483 0.104442 -0.0536111 -0.021483 0.106435 -0.0495366 -0.021483 0.108226 -0.0454887 -0.021483 0.109826 -0.0414774 -0.021483 0.111243 -0.0375114 -0.021483 0.112487 -0.0335985 -0.021483 0.113567 -0.0297454 -0.021483 0.114492 -0.0259578 -0.021483 0.115272 -0.0222404 -0.021483 0.116431 -0.0150319 -0.021483 0.116828 -0.0115463 -0.021483 0.117387 -0.00158638 -0.021483 0.117298 -0.00482252 -0.021483 0.115066 -0.00473076 -0.0185002 0.117115 -0.00814279 -0.021483 0.117387 0.00158638 -0.021483 0.117298 0.00482252 -0.021483 0.117115 0.00814279 -0.021483 0.115915 0.0185974 -0.021483 0.116431 0.0150319 -0.021483 0.114216 0.0147458 -0.0185002 0.116828 0.0115463 -0.021483 0.115272 0.0222404 -0.021483 0.114492 0.0259578 -0.021483 0.113567 0.0297454 -0.021483 0.112487 0.0335985 -0.021483 0.111243 0.0375114 -0.021483 0.109826 0.0414774 -0.021483 0.108226 0.0454887 -0.021483 0.102239 0.0577011 -0.021483 0.0998182 0.0617941 -0.021483 0.0971723 0.0658767 -0.021483 0.0942944 0.0699339 -0.021483 0.091179 0.0739499 -0.021483 0.0878216 0.0779073 -0.021483 0.0774795 0.0824943 -0.0155526 0.0735322 0.0860314 -0.0155526 0.0748249 0.0875438 -0.0185002 0.0762763 0.0892419 -0.021483 0.0554468 0.0986612 -0.0155526 0.0564216 0.100396 -0.0185002 0.057516 0.102343 -0.021483 0.0341265 0.107906 -0.0155526 0.0284014 0.109552 -0.0155526 0.0289007 0.111478 -0.0185002 0.0225581 0.110903 -0.0155526 0.0229547 0.112853 -0.0185002 0.0166197 0.111947 -0.0155526 0.0169119 0.113915 -0.0185002 0.0106104 0.112676 -0.0155526 0.0107969 0.114656 -0.0185002 0.0110064 0.11688 -0.021483 -0.0254931 0.110266 -0.0155526 -0.0312801 0.108766 -0.0155526 -0.03183 0.110678 -0.0185002 -0.036938 0.106976 -0.0155526 -0.0375874 0.108857 -0.0185002 -0.0424464 0.104913 -0.0155526 -0.0431926 0.106757 -0.0185002 -0.0440305 0.108828 -0.021483 -0.0703795 0.0864126 -0.0126994 -0.0714703 0.0877518 -0.0155526 -0.066147 0.0896939 -0.0126994 -0.0696789 0.094483 -0.021483 -0.0816895 0.0758106 -0.0126994 -0.078153 0.0794514 -0.0126994 -0.0823259 0.0836937 -0.021483 -0.0860513 0.0798584 -0.021483 -0.0895308 0.075937 -0.021483 -0.103367 0.0556549 -0.021483 -0.105464 0.0515712 -0.021483 -0.107355 0.0475087 -0.021483 -0.10905 0.0434779 -0.021483 -0.110557 0.0394882 -0.021483 -0.111886 0.0355479 -0.021483 -0.11561 0.0204094 -0.021483 -0.114899 0.02409 -0.021483 -0.112713 0.0236317 -0.0185002 -0.114048 0.0278431 -0.021483 -0.116189 0.0168048 -0.021483 -0.114425 0.0130263 -0.0185002 -0.117354 0.0031939 -0.021483 -0.117219 0.00647218 -0.021483 -0.114989 -0.00634903 -0.0185002 -0.113978 -0.016485 -0.0185002 -0.11341 -0.0200211 -0.0185002 -0.112713 -0.0236317 -0.0185002 -0.103827 -0.0363304 -0.01 -0.104953 -0.0374866 -0.0126994 -0.106215 -0.033746 -0.0126994 -0.110896 -0.0310616 -0.0185002 -0.109757 -0.0348715 -0.0185002 -0.108453 -0.0387368 -0.0185002 -0.106975 -0.0426506 -0.0185002 -0.105312 -0.0466047 -0.0185002 -0.103457 -0.0505899 -0.0185002 -0.1014 -0.0545959 -0.0185002 -0.0991333 -0.0586111 -0.0185002 -0.0880645 -0.0683012 -0.0126994 -0.0878913 -0.0661447 -0.01 -0.0860017 -0.0685836 -0.01 -0.0939405 -0.0666173 -0.0185002 -0.0849926 -0.0720879 -0.0126994 -0.0863099 -0.0732051 -0.0155526 -0.0878271 -0.0744921 -0.0185002 -0.0844138 -0.0783388 -0.0185002 -0.0807594 -0.0821011 -0.0185002 -0.0727267 -0.0892944 -0.0185002 -0.06169 -0.0928157 -0.0126994 -0.0637474 -0.0959111 -0.0185002 -0.0538733 -0.101786 -0.0185002 -0.0417986 -0.103312 -0.0126994 -0.0424464 -0.104913 -0.0155526 -0.0363743 -0.105344 -0.0126994 -0.0375874 -0.108857 -0.0185002 -0.00772041 -0.114905 -0.0185002 0.00448598 -0.111357 -0.0126994 0.0045555 -0.113082 -0.0155526 0.0104485 -0.110956 -0.0126994 0.0106104 -0.112676 -0.0155526 0.0163661 -0.110239 -0.0126994 0.0166197 -0.111947 -0.0155526 0.0222138 -0.109211 -0.0126994 0.0225581 -0.110903 -0.0155526 0.0279679 -0.107881 -0.0126994 0.0289007 -0.111478 -0.0185002 0.0459322 -0.105607 -0.0185002 0.0546006 -0.0971555 -0.0126994 0.0554468 -0.0986612 -0.0155526 0.0593797 -0.0943105 -0.0126994 0.06136 -0.0974558 -0.0185002 0.0682917 -0.0880719 -0.0126994 0.07241 -0.0847184 -0.0126994 0.0748249 -0.0875438 -0.0185002 0.0799505 -0.0776423 -0.0126994 0.0833701 -0.0739583 -0.0126994 0.0846622 -0.0751045 -0.0155526 0.0861505 -0.0764248 -0.0185002 0.089444 -0.0725427 -0.0185002 0.0925001 -0.0686032 -0.0185002 0.0953232 -0.0646232 -0.0185002 0.0979188 -0.0606183 -0.0185002 0.100293 -0.0566031 -0.0185002 0.102454 -0.052591 -0.0185002 0.104409 -0.048594 -0.0185002 0.106167 -0.0446231 -0.0185002 0.107736 -0.0406881 -0.0185002 0.109127 -0.0367976 -0.0185002 0.110347 -0.0329592 -0.0185002 0.112313 -0.0254638 -0.0185002 0.113078 -0.0218172 -0.0185002 0.113709 -0.0182435 -0.0185002 0.114216 -0.0147458 -0.0185002 0.114605 -0.0113266 -0.0185002 0.114886 -0.00798785 -0.0185002 0.115153 -0.00155619 -0.0185002 0.115153 0.00155619 -0.0185002 0.115066 0.00473076 -0.0185002 0.114886 0.00798785 -0.0185002 0.114605 0.0113266 -0.0185002 0.113709 0.0182435 -0.0185002 0.106513 0.027475 -0.01 0.10781 0.0282377 -0.0126994 0.108688 0.024642 -0.0126994 0.113078 0.0218172 -0.0185002 0.112313 0.0254638 -0.0185002 0.111406 0.0291794 -0.0185002 0.110347 0.0329592 -0.0185002 0.109127 0.0367976 -0.0185002 0.106167 0.0446231 -0.0185002 0.0970565 0.0547763 -0.0126994 0.0991476 0.0508937 -0.0126994 0.0962747 0.0532089 -0.01 0.102454 0.052591 -0.0185002 0.100293 0.0566031 -0.0185002 0.0979188 0.0606183 -0.0185002 0.0953232 0.0646232 -0.0185002 0.0925001 0.0686032 -0.0185002 0.089444 0.0725427 -0.0185002 0.0799505 0.0776423 -0.0126994 0.076297 0.0812353 -0.0126994 0.0788415 0.0839446 -0.0185002 0.0682917 0.0880719 -0.0126994 0.0639461 0.091276 -0.0126994 0.0660788 0.09432 -0.0185002 0.0496197 0.0997913 -0.0126994 0.0444498 0.102199 -0.0126994 0.0451387 0.103783 -0.0155526 0.0391061 0.104361 -0.0126994 0.0397121 0.105978 -0.0155526 0.0336057 0.106259 -0.0126994 0.0347264 0.109803 -0.0185002 0.00448598 0.111357 -0.0126994 -0.00149586 0.111437 -0.0126994 -0.00151905 0.113164 -0.0155526 -0.00747125 0.111196 -0.0126994 -0.00758704 0.11292 -0.0155526 -0.0134144 0.110637 -0.0126994 -0.0136223 0.112351 -0.0155526 -0.0193002 0.109763 -0.0126994 -0.0195993 0.111464 -0.0155526 -0.025104 0.108583 -0.0126994 -0.0259413 0.112204 -0.0185002 -0.0470575 0.101025 -0.0126994 -0.0521346 0.0985007 -0.0126994 -0.0529426 0.100027 -0.0155526 -0.0570161 0.0957579 -0.0126994 -0.0589176 0.0989515 -0.0185002 -0.068353 0.0926852 -0.0185002 -0.0743826 0.0829918 -0.0126994 -0.0755354 0.084278 -0.0155526 -0.0768633 0.0857596 -0.0185002 -0.0807594 0.0821011 -0.0185002 -0.0844138 0.0783388 -0.0185002 -0.0880645 0.0683012 -0.0126994 -0.0909087 0.0644673 -0.0126994 -0.0923176 0.0654664 -0.0155526 -0.0939405 0.0666173 -0.0185002 -0.0981274 0.0528339 -0.0126994 -0.0959339 0.0567195 -0.0126994 -0.0962744 0.0532093 -0.01 -0.0991333 0.0586111 -0.0185002 -0.1014 0.0545959 -0.0185002 -0.103457 0.0505899 -0.0185002 -0.105312 0.0466047 -0.0185002 -0.106975 0.0426506 -0.0185002 -0.108453 0.0387368 -0.0185002 -0.109757 0.0348715 -0.0185002 -0.110896 0.0310616 -0.0185002 -0.111878 0.0273133 -0.0185002 -0.111451 0.0196752 -0.0155526 -0.112009 0.0162002 -0.0155526 -0.113978 0.016485 -0.0185002 -0.11341 0.0200211 -0.0185002 -0.114989 0.00634903 -0.0185002 -0.110732 -0.0126059 -0.0126994 -0.112448 -0.0128012 -0.0155526 -0.111055 -0.00933575 -0.0126994 -0.112009 -0.0162002 -0.0155526 -0.111451 -0.0196752 -0.0155526 -0.110766 -0.0232234 -0.0155526 -0.109945 -0.0268414 -0.0155526 -0.10898 -0.030525 -0.0155526 -0.107861 -0.034269 -0.0155526 -0.10658 -0.0380676 -0.0155526 -0.105127 -0.0419138 -0.0155526 -0.103493 -0.0457995 -0.0155526 -0.0996482 -0.0536527 -0.0155526 -0.0949794 -0.061541 -0.0155526 -0.0923176 -0.0654664 -0.0155526 -0.0894293 -0.0693597 -0.0155526 -0.0829555 -0.0769855 -0.0155526 -0.0685842 -0.0860012 -0.01 -0.0709692 -0.0840439 -0.01 -0.0714703 -0.0877518 -0.0155526 -0.0504884 -0.0977288 -0.01 -0.0532093 -0.0962744 -0.01 -0.0529426 -0.100027 -0.0155526 -0.0308027 -0.107106 -0.0126994 -0.0184261 -0.108446 -0.01 -0.0193002 -0.109763 -0.0126994 -0.0214601 -0.107886 -0.01 -0.0123162 -0.109308 -0.01 -0.0134144 -0.110637 -0.0126994 -0.0153772 -0.10892 -0.01 -0.00616814 -0.109827 -0.01 -0.00924585 -0.109611 -0.01 -0.00758704 -0.11292 -0.0155526 0.039228 -0.102768 -0.01 0.0391061 -0.104361 -0.0126994 0.0363304 -0.103827 -0.01 0.0449288 -0.100406 -0.01 0.042095 -0.101627 -0.01 0.0451387 -0.103783 -0.0155526 0.0685836 -0.0860017 -0.01 0.0661447 -0.0878913 -0.01 0.0693501 -0.0894369 -0.0155526 0.0799325 -0.0755698 -0.01 0.0777815 -0.077782 -0.01 0.0811896 -0.0788457 -0.0155526 0.0878988 -0.0712895 -0.0155526 0.0936764 -0.0635068 -0.0155526 0.0985607 -0.0556253 -0.0155526 0.102606 -0.0477545 -0.0155526 0.104333 -0.0438522 -0.0155526 0.107241 -0.0361619 -0.0155526 0.108688 -0.024642 -0.0126994 0.110373 -0.0250239 -0.0155526 0.10781 -0.0282377 -0.0126994 0.111125 -0.0214403 -0.0155526 0.111745 -0.0179283 -0.0155526 0.112243 -0.0144911 -0.0155526 0.112625 -0.011131 -0.0155526 0.112902 -0.00784985 -0.0155526 0.113079 -0.00464903 -0.0155526 0.113164 -0.00152931 -0.0155526 0.113164 0.00152931 -0.0155526 0.113079 0.00464903 -0.0155526 0.112902 0.00784985 -0.0155526 0.112625 0.011131 -0.0155526 0.112243 0.0144911 -0.0155526 0.111745 0.0179283 -0.0155526 0.111125 0.0214403 -0.0155526 0.110373 0.0250239 -0.0155526 0.109481 0.0286753 -0.0155526 0.10844 0.0323898 -0.0155526 0.102741 0.043183 -0.0126994 0.104333 0.0438522 -0.0155526 0.104259 0.039375 -0.0126994 0.102606 0.0477545 -0.0155526 0.100684 0.0516824 -0.0155526 0.0985607 0.0556253 -0.0155526 0.0962272 0.0595711 -0.0155526 0.0909021 0.067418 -0.0155526 0.077782 0.0777815 -0.01 0.0799329 0.0755694 -0.01 0.0811896 0.0788457 -0.0155526 0.066145 0.087891 -0.01 0.0685842 0.0860012 -0.01 0.0693501 0.0894369 -0.0155526 0.0532093 0.0962744 -0.01 0.0546006 0.0971555 -0.0126994 0.0558884 0.0947443 -0.01 0.0477275 0.0991065 -0.01 0.0504884 0.0977288 -0.01 0.0503887 0.101338 -0.0155526 0.0214601 0.107886 -0.01 0.0222138 0.109211 -0.0126994 0.0244774 0.107242 -0.01 0.0153772 0.10892 -0.01 0.0163661 0.110239 -0.0126994 0.0184261 0.108446 -0.01 0.00924585 0.109611 -0.01 0.0104485 0.110956 -0.0126994 0.0123162 0.109308 -0.01 0.00308534 0.109957 -0.01 0.00616814 0.109827 -0.01 0.0045555 0.113082 -0.0155526 -0.0363304 0.103827 -0.01 -0.0363743 0.105344 -0.0126994 -0.0334044 0.104805 -0.01 -0.042095 0.101627 -0.01 -0.0417986 0.103312 -0.0126994 -0.039228 0.102768 -0.01 -0.0477269 0.0991067 -0.01 -0.0449288 0.100406 -0.01 -0.0477868 0.10259 -0.0155526 -0.0661447 0.0878913 -0.01 -0.0636538 0.0897118 -0.01 -0.0671721 0.091084 -0.0155526 -0.0793642 0.0806827 -0.0155526 -0.087891 0.066145 -0.01 -0.0860012 0.0685842 -0.01 -0.0894293 0.0693597 -0.0155526 -0.0949794 0.061541 -0.0155526 -0.0974207 0.0575986 -0.0155526 -0.0996482 0.0536527 -0.0155526 -0.10167 0.0497159 -0.0155526 -0.105127 0.0419138 -0.0155526 -0.10658 0.0380676 -0.0155526 -0.10898 0.030525 -0.0155526 -0.109945 0.0268414 -0.0155526 -0.110766 0.0232234 -0.0155526 -0.113002 0.00623934 -0.0155526 -0.111055 0.00933575 -0.0126994 -0.109308 -0.012316 -0.01 -0.110299 -0.015953 -0.0126994 -0.10975 -0.0193749 -0.0126994 -0.109075 -0.022869 -0.0126994 -0.108267 -0.0264318 -0.0126994 -0.107317 -0.0300591 -0.0126994 -0.103522 -0.0412741 -0.0126994 -0.0991067 -0.0477269 -0.01 -0.0962747 -0.0532089 -0.01 -0.0935298 -0.0606018 -0.0126994 -0.0909087 -0.0644673 -0.0126994 -0.0799329 -0.0755694 -0.01 -0.0743826 -0.0829918 -0.0126994 -0.063654 -0.0897116 -0.01 -0.0570161 -0.0957579 -0.0126994 -0.0477275 -0.0991065 -0.01 -0.0449289 -0.100406 -0.01 -0.0392287 -0.102767 -0.01 -0.0334045 -0.104805 -0.01 -0.025104 -0.108583 -0.0126994 2.80664e-16 -0.11 -0.01 -0.00308534 -0.109957 -0.01 0.00616737 -0.109827 -0.01 0.012316 -0.109308 -0.01 0.0184253 -0.108446 -0.01 0.0244771 -0.107242 -0.01 0.0336057 -0.106259 -0.0126994 0.0477269 -0.0991067 -0.01 0.0504877 -0.0977292 -0.01 0.0558881 -0.0947445 -0.01 0.0639461 -0.091276 -0.0126994 0.076297 -0.0812353 -0.0126994 0.0860012 -0.0685842 -0.01 0.0914614 -0.061113 -0.01 0.0962744 -0.0532093 -0.01 0.10104 -0.0470257 -0.0126994 0.101627 -0.0420955 -0.01 0.105605 -0.03561 -0.0126994 0.106785 -0.0318955 -0.0126994 0.106513 -0.0274758 -0.01 0.109429 -0.0211131 -0.0126994 0.11004 -0.0176547 -0.0126994 0.11053 -0.0142699 -0.0126994 0.110907 -0.0109611 -0.0126994 0.111179 -0.00773005 -0.0126994 0.111353 -0.00457808 -0.0126994 0.111437 -0.00150597 -0.0126994 0.111437 0.00150597 -0.0126994 0.111353 0.00457808 -0.0126994 0.111179 0.00773005 -0.0126994 0.110907 0.0109611 -0.0126994 0.11053 0.0142699 -0.0126994 0.11004 0.0176547 -0.0126994 0.109429 0.0211131 -0.0126994 0.106785 0.0318955 -0.0126994 0.105605 0.03561 -0.0126994 0.101627 0.042095 -0.01 0.10104 0.0470257 -0.0126994 0.0931399 0.0585232 -0.01 0.0860017 0.0685836 -0.01 0.0833701 0.0739583 -0.0126994 0.07241 0.0847184 -0.0126994 0.0593797 0.0943105 -0.0126994 0.0420955 0.101627 -0.01 0.0363309 0.103827 -0.01 0.0279679 0.107881 -0.0126994 -3.18856e-16 0.11 -0.01 -0.00308474 0.109957 -0.01 -0.00924536 0.109611 -0.01 -0.0153766 0.10892 -0.01 -0.0214598 0.107886 -0.01 -0.0308027 0.107106 -0.0126994 -0.0532089 0.0962747 -0.01 -0.06169 0.0928157 -0.0126994 -0.0709687 0.0840443 -0.01 -0.0799325 0.0755698 -0.01 -0.0849926 0.0720879 -0.0126994 -0.0935298 0.0606018 -0.0126994 -0.0991065 0.0477275 -0.01 -0.103522 0.0412741 -0.0126994 -0.103827 0.0363309 -0.01 -0.107317 0.0300591 -0.0126994 -0.108267 0.0264318 -0.0126994 -0.109075 0.022869 -0.0126994 -0.10975 0.0193749 -0.0126994 -0.110299 0.015953 -0.0126994 -0.110732 0.0126059 -0.0126994 -0.109308 0.0123162 -0.01 -0.109611 -0.00924536 -0.01 -0.10892 -0.0153766 -0.01 -0.108446 -0.0184253 -0.01 -0.107886 -0.0214598 -0.01 -0.107242 -0.0244771 -0.01 -0.106513 -0.027475 -0.01 -0.105701 -0.0304516 -0.01 -0.104805 -0.0334044 -0.01 -0.102768 -0.039228 -0.01 -0.101627 -0.042095 -0.01 -0.100406 -0.0449288 -0.01 -0.0977292 -0.0504877 -0.01 -0.0947445 -0.0558881 -0.01 -0.0931399 -0.0585232 -0.01 -0.0914618 -0.0611124 -0.01 -0.0897118 -0.0636538 -0.01 -0.0840443 -0.0709687 -0.01 -0.0820207 -0.0732981 -0.01 -0.077782 -0.0777815 -0.01 -0.0755698 -0.0799325 -0.01 -0.0732982 -0.0820206 -0.01 -0.066145 -0.087891 -0.01 -0.061113 -0.0914614 -0.01 -0.0585238 -0.0931395 -0.01 -0.0558884 -0.0947443 -0.01 -0.0420955 -0.101627 -0.01 -0.0363309 -0.103827 -0.01 -0.0304523 -0.105701 -0.01 -0.0274758 -0.106513 -0.01 -0.0244774 -0.107242 -0.01 0.00308474 -0.109957 -0.01 0.00924536 -0.109611 -0.01 0.0153766 -0.10892 -0.01 0.0214598 -0.107886 -0.01 0.027475 -0.106513 -0.01 0.0304516 -0.105701 -0.01 0.0334044 -0.104805 -0.01 0.0532089 -0.0962747 -0.01 0.0585232 -0.0931399 -0.01 0.0611124 -0.0914618 -0.01 0.0636538 -0.0897118 -0.01 0.0709687 -0.0840443 -0.01 0.0732981 -0.0820207 -0.01 0.0755694 -0.0799329 -0.01 0.0820206 -0.0732982 -0.01 0.0840439 -0.0709692 -0.01 0.087891 -0.066145 -0.01 0.0897116 -0.063654 -0.01 0.0931395 -0.0585238 -0.01 0.0947443 -0.0558884 -0.01 0.0977288 -0.0504884 -0.01 0.0991065 -0.0477275 -0.01 0.100406 -0.0449289 -0.01 0.102767 -0.0392287 -0.01 0.103827 -0.0363309 -0.01 0.104805 -0.0334045 -0.01 0.105701 -0.0304523 -0.01 0.107242 -0.0244774 -0.01 0.107886 -0.0214601 -0.01 0.108446 -0.0184261 -0.01 0.10892 -0.0153772 -0.01 0.109308 -0.0123162 -0.01 0.109611 -0.00924585 -0.01 0.109827 -0.00616814 -0.01 0.109957 -0.00308534 -0.01 0.11 8.80243e-14 -0.01 0.109957 0.00308534 -0.01 0.109827 0.00616737 -0.01 0.109611 0.00924536 -0.01 0.109308 0.012316 -0.01 0.10892 0.0153766 -0.01 0.108446 0.0184253 -0.01 0.107886 0.0214598 -0.01 0.107242 0.0244771 -0.01 0.105701 0.0304516 -0.01 0.104805 0.0334044 -0.01 0.103827 0.0363304 -0.01 0.102768 0.039228 -0.01 0.100406 0.0449288 -0.01 0.0991067 0.0477269 -0.01 0.0977292 0.0504877 -0.01 0.0947445 0.0558881 -0.01 0.0914618 0.0611124 -0.01 0.0897118 0.0636538 -0.01 0.0878913 0.0661447 -0.01 0.0840443 0.0709687 -0.01 0.0820207 0.0732981 -0.01 0.0755698 0.0799325 -0.01 0.0732982 0.0820206 -0.01 0.0709692 0.0840439 -0.01 0.063654 0.0897116 -0.01 0.061113 0.0914614 -0.01 0.0585238 0.0931395 -0.01 0.0449289 0.100406 -0.01 0.0392287 0.102767 -0.01 0.0334045 0.104805 -0.01 0.0304523 0.105701 -0.01 0.0274758 0.106513 -0.01 -0.00616737 0.109827 -0.01 -0.012316 0.109308 -0.01 -0.0184253 0.108446 -0.01 -0.0244771 0.107242 -0.01 -0.027475 0.106513 -0.01 -0.0304516 0.105701 -0.01 -0.0504877 0.0977292 -0.01 -0.0558881 0.0947445 -0.01 -0.0585232 0.0931399 -0.01 -0.0611124 0.0914618 -0.01 -0.0685836 0.0860017 -0.01 -0.0732981 0.0820207 -0.01 -0.0755694 0.0799329 -0.01 -0.0777815 0.077782 -0.01 -0.0820206 0.0732982 -0.01 -0.0840439 0.0709692 -0.01 -0.0897116 0.063654 -0.01 -0.0914614 0.061113 -0.01 -0.0931395 0.0585238 -0.01 -0.0947443 0.0558884 -0.01 -0.0977288 0.0504884 -0.01 -0.100406 0.0449289 -0.01 -0.101627 0.0420955 -0.01 -0.102767 0.0392287 -0.01 -0.104805 0.0334045 -0.01 -0.105701 0.0304523 -0.01 -0.106513 0.0274758 -0.01 -0.107242 0.0244774 -0.01 -0.107886 0.0214601 -0.01 -0.108446 0.0184261 -0.01 -0.10892 0.0153772 -0.01 -0.109611 0.00924585 -0.01 -0.109827 0.00616814 -0.01 -0.109957 0.00308534 -0.01 0.109827 -0.00616737 0.01 0.109957 -0.00308534 -0.01 0.109827 -0.00616814 -0.01 0.11 8.80243e-14 -0.01 0.109957 -0.00308534 0.01 0.11 2.45709e-15 0.01 0.109308 -0.0123162 -0.01 0.10892 -0.0153772 -0.01 0.10892 -0.0153766 0.01 0.109308 -0.012316 0.01 0.109611 -0.00924536 0.01 0.109611 -0.00924585 -0.01 0.107242 -0.0244771 0.01 0.107886 -0.0214601 -0.01 0.107242 -0.0244774 -0.01 0.107886 -0.0214598 0.01 0.108446 -0.0184253 0.01 0.108446 -0.0184261 -0.01 0.104805 -0.0334045 -0.01 0.104805 -0.0334044 0.01 0.105701 -0.0304523 -0.01 0.106513 -0.0274758 -0.01 0.105701 -0.0304516 0.01 0.106513 -0.027475 0.01 0.102767 -0.0392287 -0.01 0.101627 -0.0420955 -0.01 0.101627 -0.042095 0.01 0.103827 -0.0363304 0.01 0.103827 -0.0363309 -0.01 0.102768 -0.039228 0.01 0.0977292 -0.0504877 0.01 0.0991065 -0.0477275 -0.01 0.0977288 -0.0504884 -0.01 0.0991067 -0.0477269 0.01 0.100406 -0.0449288 0.01 0.100406 -0.0449289 -0.01 0.0931395 -0.0585238 -0.01 0.0931399 -0.0585232 0.01 0.0947443 -0.0558884 -0.01 0.0962744 -0.0532093 -0.01 0.0947445 -0.0558881 0.01 0.0962747 -0.0532089 0.01 0.0897116 -0.063654 -0.01 0.087891 -0.066145 -0.01 0.0878913 -0.0661447 0.01 0.0914618 -0.0611124 0.01 0.0914614 -0.061113 -0.01 0.0897118 -0.0636538 0.01 0.0820207 -0.0732981 0.01 0.0840439 -0.0709692 -0.01 0.0820206 -0.0732982 -0.01 0.0840443 -0.0709687 0.01 0.0860017 -0.0685836 0.01 0.0860012 -0.0685842 -0.01 0.0755694 -0.0799329 -0.01 0.0755698 -0.0799325 0.01 0.0777815 -0.077782 -0.01 0.0799325 -0.0755698 -0.01 0.077782 -0.0777815 0.01 0.0799329 -0.0755694 0.01 0.0709687 -0.0840443 -0.01 0.0685836 -0.0860017 -0.01 0.0685842 -0.0860012 0.01 0.0732982 -0.0820206 0.01 0.0732981 -0.0820207 -0.01 0.0709692 -0.0840439 0.01 0.061113 -0.0914614 0.01 0.0636538 -0.0897118 -0.01 0.0611124 -0.0914618 -0.01 0.063654 -0.0897116 0.01 0.066145 -0.087891 0.01 0.0661447 -0.0878913 -0.01 0.0532089 -0.0962747 -0.01 0.0532093 -0.0962744 0.01 0.0558881 -0.0947445 -0.01 0.0585232 -0.0931399 -0.01 0.0558884 -0.0947443 0.01 0.0585238 -0.0931395 0.01 0.0477269 -0.0991067 -0.01 0.0449288 -0.100406 -0.01 0.0449289 -0.100406 0.01 0.0504884 -0.0977288 0.01 0.0504877 -0.0977292 -0.01 0.0477275 -0.0991065 0.01 0.0363309 -0.103827 0.01 0.039228 -0.102768 -0.01 0.0363304 -0.103827 -0.01 0.0392287 -0.102767 0.01 0.0420955 -0.101627 0.01 0.042095 -0.101627 -0.01 0.027475 -0.106513 -0.01 0.0274758 -0.106513 0.01 0.0304516 -0.105701 -0.01 0.0334044 -0.104805 -0.01 0.0304523 -0.105701 0.01 0.0334045 -0.104805 0.01 0.0214598 -0.107886 -0.01 0.0184253 -0.108446 -0.01 0.0184261 -0.108446 0.01 0.0244774 -0.107242 0.01 0.0244771 -0.107242 -0.01 0.0214601 -0.107886 0.01 0.00924585 -0.109611 0.01 0.012316 -0.109308 -0.01 0.00924536 -0.109611 -0.01 0.0123162 -0.109308 0.01 0.0153772 -0.10892 0.01 0.0153766 -0.10892 -0.01 2.80664e-16 -0.11 -0.01 -3.20632e-16 -0.11 0.01 0.00308474 -0.109957 -0.01 0.00616737 -0.109827 -0.01 0.00308534 -0.109957 0.01 0.00616814 -0.109827 0.01 -0.00616814 -0.109827 -0.01 -0.00924585 -0.109611 -0.01 -0.00924536 -0.109611 0.01 -0.00308474 -0.109957 0.01 -0.00308534 -0.109957 -0.01 -0.00616737 -0.109827 0.01 -0.0184253 -0.108446 0.01 -0.0153772 -0.10892 -0.01 -0.0184261 -0.108446 -0.01 -0.0153766 -0.10892 0.01 -0.012316 -0.109308 0.01 -0.0123162 -0.109308 -0.01 -0.0274758 -0.106513 -0.01 -0.027475 -0.106513 0.01 -0.0244774 -0.107242 -0.01 -0.0214601 -0.107886 -0.01 -0.0244771 -0.107242 0.01 -0.0214598 -0.107886 0.01 -0.0334045 -0.104805 -0.01 -0.0363309 -0.103827 -0.01 -0.0363304 -0.103827 0.01 -0.0304516 -0.105701 0.01 -0.0304523 -0.105701 -0.01 -0.0334044 -0.104805 0.01 -0.0449288 -0.100406 0.01 -0.0420955 -0.101627 -0.01 -0.0449289 -0.100406 -0.01 -0.042095 -0.101627 0.01 -0.039228 -0.102768 0.01 -0.0392287 -0.102767 -0.01 -0.0532093 -0.0962744 -0.01 -0.0532089 -0.0962747 0.01 -0.0504884 -0.0977288 -0.01 -0.0477275 -0.0991065 -0.01 -0.0504877 -0.0977292 0.01 -0.0477269 -0.0991067 0.01 -0.0585238 -0.0931395 -0.01 -0.061113 -0.0914614 -0.01 -0.0611124 -0.0914618 0.01 -0.0558881 -0.0947445 0.01 -0.0558884 -0.0947443 -0.01 -0.0585232 -0.0931399 0.01 -0.0685836 -0.0860017 0.01 -0.066145 -0.087891 -0.01 -0.0685842 -0.0860012 -0.01 -0.0661447 -0.0878913 0.01 -0.0636538 -0.0897118 0.01 -0.063654 -0.0897116 -0.01 -0.0755698 -0.0799325 -0.01 -0.0755694 -0.0799329 0.01 -0.0732982 -0.0820206 -0.01 -0.0709692 -0.0840439 -0.01 -0.0732981 -0.0820207 0.01 -0.0709687 -0.0840443 0.01 -0.0799329 -0.0755694 -0.01 -0.0820207 -0.0732981 -0.01 -0.0820206 -0.0732982 0.01 -0.0777815 -0.077782 0.01 -0.077782 -0.0777815 -0.01 -0.0799325 -0.0755698 0.01 -0.087891 -0.066145 0.01 -0.0860017 -0.0685836 -0.01 -0.0878913 -0.0661447 -0.01 -0.0860012 -0.0685842 0.01 -0.0840439 -0.0709692 0.01 -0.0840443 -0.0709687 -0.01 -0.0931399 -0.0585232 -0.01 -0.0931395 -0.0585238 0.01 -0.0914618 -0.0611124 -0.01 -0.0897118 -0.0636538 -0.01 -0.0914614 -0.061113 0.01 -0.0897116 -0.063654 0.01 -0.0962747 -0.0532089 -0.01 -0.0977292 -0.0504877 -0.01 -0.0977288 -0.0504884 0.01 -0.0947443 -0.0558884 0.01 -0.0947445 -0.0558881 -0.01 -0.0962744 -0.0532093 0.01 -0.101627 -0.0420955 0.01 -0.100406 -0.0449288 -0.01 -0.101627 -0.042095 -0.01 -0.100406 -0.0449289 0.01 -0.0991065 -0.0477275 0.01 -0.0991067 -0.0477269 -0.01 -0.104805 -0.0334044 -0.01 -0.104805 -0.0334045 0.01 -0.103827 -0.0363304 -0.01 -0.102768 -0.039228 -0.01 -0.103827 -0.0363309 0.01 -0.102767 -0.0392287 0.01 -0.106513 -0.027475 -0.01 -0.107242 -0.0244771 -0.01 -0.107242 -0.0244774 0.01 -0.105701 -0.0304523 0.01 -0.105701 -0.0304516 -0.01 -0.106513 -0.0274758 0.01 -0.10892 -0.0153772 0.01 -0.108446 -0.0184253 -0.01 -0.10892 -0.0153766 -0.01 -0.108446 -0.0184261 0.01 -0.107886 -0.0214601 0.01 -0.107886 -0.0214598 -0.01 -0.109827 -0.00616737 -0.01 -0.109827 -0.00616814 0.01 -0.109611 -0.00924536 -0.01 -0.109308 -0.012316 -0.01 -0.109611 -0.00924585 0.01 -0.109308 -0.0123162 0.01 -0.11 0 -0.01 -0.109957 0.00308534 -0.01 -0.109957 0.00308534 0.01 -0.109957 -0.00308534 0.01 -0.109957 -0.00308534 -0.01 -0.11 0 0.01 -0.109308 0.012316 0.01 -0.109611 0.00924585 -0.01 -0.109308 0.0123162 -0.01 -0.109611 0.00924536 0.01 -0.109827 0.00616737 0.01 -0.109827 0.00616814 -0.01 -0.107886 0.0214601 -0.01 -0.107886 0.0214598 0.01 -0.108446 0.0184261 -0.01 -0.10892 0.0153772 -0.01 -0.108446 0.0184253 0.01 -0.10892 0.0153766 0.01 -0.106513 0.0274758 -0.01 -0.105701 0.0304523 -0.01 -0.105701 0.0304516 0.01 -0.107242 0.0244771 0.01 -0.107242 0.0244774 -0.01 -0.106513 0.027475 0.01 -0.102768 0.039228 0.01 -0.103827 0.0363309 -0.01 -0.102767 0.0392287 -0.01 -0.103827 0.0363304 0.01 -0.104805 0.0334044 0.01 -0.104805 0.0334045 -0.01 -0.0991065 0.0477275 -0.01 -0.0991067 0.0477269 0.01 -0.100406 0.0449289 -0.01 -0.101627 0.0420955 -0.01 -0.100406 0.0449288 0.01 -0.101627 0.042095 0.01 -0.0962744 0.0532093 -0.01 -0.0947443 0.0558884 -0.01 -0.0947445 0.0558881 0.01 -0.0977292 0.0504877 0.01 -0.0977288 0.0504884 -0.01 -0.0962747 0.0532089 0.01 -0.0897118 0.0636538 0.01 -0.0914614 0.061113 -0.01 -0.0897116 0.063654 -0.01 -0.0914618 0.0611124 0.01 -0.0931399 0.0585232 0.01 -0.0931395 0.0585238 -0.01 -0.0840439 0.0709692 -0.01 -0.0840443 0.0709687 0.01 -0.0860012 0.0685842 -0.01 -0.087891 0.066145 -0.01 -0.0860017 0.0685836 0.01 -0.0878913 0.0661447 0.01 -0.0799325 0.0755698 -0.01 -0.0777815 0.077782 -0.01 -0.077782 0.0777815 0.01 -0.0820207 0.0732981 0.01 -0.0820206 0.0732982 -0.01 -0.0799329 0.0755694 0.01 -0.0709692 0.0840439 0.01 -0.0732981 0.0820207 -0.01 -0.0709687 0.0840443 -0.01 -0.0732982 0.0820206 0.01 -0.0755698 0.0799325 0.01 -0.0755694 0.0799329 -0.01 -0.0636538 0.0897118 -0.01 -0.063654 0.0897116 0.01 -0.0661447 0.0878913 -0.01 -0.0685836 0.0860017 -0.01 -0.066145 0.087891 0.01 -0.0685842 0.0860012 0.01 -0.0585232 0.0931399 -0.01 -0.0558881 0.0947445 -0.01 -0.0558884 0.0947443 0.01 -0.061113 0.0914614 0.01 -0.0611124 0.0914618 -0.01 -0.0585238 0.0931395 0.01 -0.0477275 0.0991065 0.01 -0.0504877 0.0977292 -0.01 -0.0477269 0.0991067 -0.01 -0.0504884 0.0977288 0.01 -0.0532093 0.0962744 0.01 -0.0532089 0.0962747 -0.01 -0.039228 0.102768 -0.01 -0.0392287 0.102767 0.01 -0.042095 0.101627 -0.01 -0.0449288 0.100406 -0.01 -0.0420955 0.101627 0.01 -0.0449289 0.100406 0.01 -0.0334044 0.104805 -0.01 -0.0304516 0.105701 -0.01 -0.0304523 0.105701 0.01 -0.0363309 0.103827 0.01 -0.0363304 0.103827 -0.01 -0.0334045 0.104805 0.01 -0.0214601 0.107886 0.01 -0.0244771 0.107242 -0.01 -0.0214598 0.107886 -0.01 -0.0244774 0.107242 0.01 -0.0274758 0.106513 0.01 -0.027475 0.106513 -0.01 -0.012316 0.109308 -0.01 -0.0123162 0.109308 0.01 -0.0153766 0.10892 -0.01 -0.0184253 0.108446 -0.01 -0.0153772 0.10892 0.01 -0.0184261 0.108446 0.01 -0.00616737 0.109827 -0.01 -0.00308474 0.109957 -0.01 -0.00308534 0.109957 0.01 -0.00924585 0.109611 0.01 -0.00924536 0.109611 -0.01 -0.00616814 0.109827 0.01 -3.18856e-16 0.11 -0.01 0.00308534 0.109957 -0.01 0.00308474 0.109957 0.01 3.08198e-16 0.11 0.01 0.00616814 0.109827 -0.01 0.00616737 0.109827 0.01 0.00924536 0.109611 0.01 0.00924585 0.109611 -0.01 0.0123162 0.109308 -0.01 0.012316 0.109308 0.01 0.0153772 0.10892 -0.01 0.0153766 0.10892 0.01 0.0184253 0.108446 0.01 0.0184261 0.108446 -0.01 0.0214601 0.107886 -0.01 0.0214598 0.107886 0.01 0.0244774 0.107242 -0.01 0.0244771 0.107242 0.01 0.027475 0.106513 0.01 0.0274758 0.106513 -0.01 0.0304523 0.105701 -0.01 0.0304516 0.105701 0.01 0.0334045 0.104805 -0.01 0.0334044 0.104805 0.01 0.0363304 0.103827 0.01 0.0363309 0.103827 -0.01 0.0392287 0.102767 -0.01 0.039228 0.102768 0.01 0.0420955 0.101627 -0.01 0.042095 0.101627 0.01 0.0449288 0.100406 0.01 0.0449289 0.100406 -0.01 0.0477275 0.0991065 -0.01 0.0477269 0.0991067 0.01 0.0504884 0.0977288 -0.01 0.0504877 0.0977292 0.01 0.0532089 0.0962747 0.01 0.0532093 0.0962744 -0.01 0.0558884 0.0947443 -0.01 0.0558881 0.0947445 0.01 0.0585238 0.0931395 -0.01 0.0585232 0.0931399 0.01 0.0611124 0.0914618 0.01 0.061113 0.0914614 -0.01 0.063654 0.0897116 -0.01 0.0636538 0.0897118 0.01 0.066145 0.087891 -0.01 0.0661447 0.0878913 0.01 0.0685836 0.0860017 0.01 0.0685842 0.0860012 -0.01 0.0709692 0.0840439 -0.01 0.0709687 0.0840443 0.01 0.0732982 0.0820206 -0.01 0.0732981 0.0820207 0.01 0.0755694 0.0799329 0.01 0.0755698 0.0799325 -0.01 0.077782 0.0777815 -0.01 0.0777815 0.077782 0.01 0.0799329 0.0755694 -0.01 0.0799325 0.0755698 0.01 0.0820206 0.0732982 0.01 0.0820207 0.0732981 -0.01 0.0840443 0.0709687 -0.01 0.0840439 0.0709692 0.01 0.0860017 0.0685836 -0.01 0.0860012 0.0685842 0.01 0.087891 0.066145 0.01 0.0878913 0.0661447 -0.01 0.0897118 0.0636538 -0.01 0.0897116 0.063654 0.01 0.0914618 0.0611124 -0.01 0.0914614 0.061113 0.01 0.0931395 0.0585238 0.01 0.0931399 0.0585232 -0.01 0.0947445 0.0558881 -0.01 0.0947443 0.0558884 0.01 0.0962747 0.0532089 -0.01 0.0962744 0.0532093 0.01 0.0977288 0.0504884 0.01 0.0977292 0.0504877 -0.01 0.0991067 0.0477269 -0.01 0.0991065 0.0477275 0.01 0.100406 0.0449288 -0.01 0.100406 0.0449289 0.01 0.101627 0.0420955 0.01 0.101627 0.042095 -0.01 0.102768 0.039228 -0.01 0.102767 0.0392287 0.01 0.103827 0.0363304 -0.01 0.103827 0.0363309 0.01 0.104805 0.0334045 0.01 0.104805 0.0334044 -0.01 0.105701 0.0304516 -0.01 0.105701 0.0304523 0.01 0.106513 0.027475 -0.01 0.106513 0.0274758 0.01 0.107242 0.0244774 0.01 0.107242 0.0244771 -0.01 0.107886 0.0214598 -0.01 0.107886 0.0214601 0.01 0.108446 0.0184253 -0.01 0.108446 0.0184261 0.01 0.10892 0.0153772 0.01 0.10892 0.0153766 -0.01 0.109308 0.012316 -0.01 0.109308 0.0123162 0.01 0.109611 0.00924536 -0.01 0.109611 0.00924585 0.01 0.109827 0.00616814 0.01 0.109827 0.00616737 -0.01 0.109957 0.00308534 -0.01 0.109957 0.00308534 0.01 - - - - - - - - - - -0.564297 -0.660218 0.495662 -0.596058 -0.66699 0.447033 -0.594589 -0.633074 0.495662 0.794221 -0.351473 0.495662 0.806758 -0.321653 0.495662 0.826425 -0.342319 0.447033 0.537888 -0.714729 0.447033 0.515489 -0.698992 0.495662 0.557721 -0.699363 0.447033 0.49591 0.608882 0.619141 0.466086 0.632003 0.619141 0.483769 0.65598 0.57936 0.548474 -0.673421 0.495662 0.8165 -0.365361 0.447033 -0.866424 0.060241 0.495662 -0.89311 0.0501621 0.447033 -0.891352 0.0751876 0.447033 0.577116 -0.683446 0.447033 0.780228 -0.381527 0.495662 0.805931 -0.38812 0.447033 0.527188 -0.535946 0.65942 0.550683 -0.559832 0.619141 0.501754 -0.559829 0.65942 0.764716 -0.411739 0.495662 0.794728 -0.41057 0.447033 0.747621 -0.44202 0.495662 0.770458 -0.454483 0.447033 0.757408 -0.475914 0.447033 0.8357 -0.319008 0.447033 0.782902 -0.432696 0.447033 0.609053 -0.619172 0.495662 0.650009 -0.614532 0.447033 0.632518 -0.632521 0.447033 0.708459 -0.502399 0.495662 0.728886 -0.472275 0.495662 0.743762 -0.496969 0.447033 0.714727 -0.53789 0.447033 0.729533 -0.517632 0.447033 0.66699 -0.596059 0.447033 0.662355 -0.561787 0.495662 0.683443 -0.577119 0.447033 0.686295 -0.532277 0.495662 0.69936 -0.557725 0.447033 0.636614 -0.590798 0.495662 0.61453 -0.650011 0.447033 0.57967 -0.646763 0.495662 0.596058 -0.66699 0.447033 0.517631 -0.729534 0.447033 0.444331 -0.74625 0.495662 0.454482 -0.770459 0.447033 0.432694 -0.782903 0.447033 0.274953 -0.796293 0.538812 0.315956 -0.780931 0.538812 0.325741 -0.805116 0.495662 0.388116 -0.805933 0.447033 0.40629 -0.767625 0.495662 0.410566 -0.794731 0.447033 0.266025 -0.770437 0.57936 0.305696 -0.755574 0.57936 0.275047 -0.372958 0.886144 0.323763 -0.439016 0.838118 0.256514 -0.385939 0.886144 0.344157 -0.738849 0.57936 0.355707 -0.763645 0.538812 0.333574 -0.630239 0.70109 0.351679 -0.664445 0.65942 0.301089 -0.646389 0.70109 0.431041 -0.334307 0.838118 0.416006 -0.352842 0.838118 0.35341 -0.29975 0.886144 0.367352 -0.694058 0.619141 0.317431 -0.681472 0.65942 0.369411 -0.555798 0.744731 0.313311 -0.526202 0.790536 0.338995 -0.510034 0.790536 0.279071 -0.468697 0.838118 0.301948 -0.454296 0.838118 0.364807 -0.61269 0.70109 0.312192 -0.589841 0.744731 0.341423 -0.573416 0.744731 -0.176327 0.0949384 0.979743 -0.0501152 0.0269831 0.998379 -0.172386 0.101921 0.979743 0.286487 -0.541274 0.790536 0.23708 -0.398173 0.886144 0.294523 -0.727956 0.619141 0.331578 -0.711843 0.619141 0.200881 -0.302236 0.931826 0.215395 -0.29207 0.931826 0.229177 -0.281385 0.931826 0.143338 -0.194363 0.9704 0.15251 -0.187253 0.9704 -0.0213473 0.052763 0.998379 0.0418673 -0.0898822 0.995072 0.0371885 -0.0919168 0.995072 -0.0751089 0.185643 0.979743 -0.0845587 0.181534 0.979743 -0.0240331 0.0515951 0.998379 -0.388667 0.190056 0.901563 -0.462618 0.249083 0.850848 -0.472002 0.230806 0.850848 -0.216982 0.242096 0.945679 -0.140435 0.142768 0.979743 -0.13366 0.14913 0.979743 -0.0399139 0.0405771 0.998379 -0.0379883 0.0423852 0.998379 -0.596352 0.321088 0.735708 -0.533702 0.287356 0.795355 -0.583021 0.344703 0.735708 -0.0359439 0.0441322 0.998379 -0.126466 0.155276 0.979743 -0.28876 0.322182 0.901563 -0.22798 0.231768 0.945679 -0.806307 0.476718 0.350154 -0.824744 0.44406 0.350154 -0.789215 0.42493 0.443366 -0.462263 0.392076 0.795355 -0.516527 0.438101 0.735708 -0.478971 0.371481 0.795355 -0.303397 0.308438 0.901563 -0.368449 0.37457 0.850848 -0.317126 0.294303 0.901563 -0.496453 0.460725 0.735708 -0.444298 0.412323 0.795355 -0.630659 0.489127 0.602514 -0.604301 0.428536 0.671697 -0.585395 0.454022 0.671697 -0.535196 0.415088 0.735708 -0.564975 0.479193 0.671697 -0.637705 0.377034 0.671697 -0.669798 0.43399 0.602514 -0.687014 0.406187 0.602514 -0.671597 0.520878 0.52692 -0.651027 0.461671 0.602514 -0.238297 0.221147 0.945679 -0.693287 0.491639 0.52692 -0.731156 0.518495 0.443366 -0.713276 0.462161 0.52692 -0.708282 0.54933 0.443366 -0.679763 0.691056 0.245689 -0.695406 0.706959 0.128917 -0.710523 0.659389 0.245689 -0.860803 0.508938 1.91753e-07 -0.880486 0.474072 1.91753e-07 -0.873139 0.470116 0.128917 -0.841474 0.411476 -0.350154 -0.870812 0.425822 -0.245689 -0.824744 0.44406 -0.350154 -0.764072 0.541836 0.350155 -0.752238 0.487406 0.443366 -0.85362 0.504691 0.128917 -0.839232 0.543773 1.91753e-07 -0.85362 0.504691 -0.128917 -0.873139 0.470116 -0.128917 -0.832229 0.539235 -0.128917 -0.832229 0.539236 0.128917 -0.813509 0.527106 0.245689 -0.808906 0.57363 0.128917 -0.856565 0.379062 -0.350154 -0.805225 0.39375 -0.443366 -0.819665 0.362733 -0.443366 -0.789215 0.42493 -0.443366 -0.729836 0.32298 -0.602514 -0.777211 0.343945 -0.52692 -0.716978 0.350598 -0.602514 -0.832605 0.331957 -0.443366 -0.78948 0.314764 -0.52692 -0.533702 0.287356 -0.795355 -0.596352 0.321088 -0.735709 -0.521771 0.30849 -0.795355 -0.741357 0.295577 -0.602514 -0.500746 0.159094 -0.850848 -0.58368 0.163488 -0.795355 -0.577689 0.18354 -0.795355 -0.677454 0.299799 -0.671697 -0.688148 0.274363 -0.671697 -0.494797 0.176729 -0.850848 -0.570826 0.203885 -0.795355 -0.412336 0.131005 -0.901563 -0.505939 0.141713 -0.850848 -0.629138 0.250836 -0.735709 -0.563043 0.224484 -0.795355 -0.637834 0.227818 -0.735709 -0.0548082 0.0153517 -0.998379 -0.194548 0.0474958 -0.979743 -0.19284 0.0540139 -0.979743 -0.30984 0.0984407 -0.945679 -0.416613 0.116692 -0.901563 0.496966 -0.743765 0.447033 0.480756 -0.723321 0.495662 -0.197212 0.0348152 -0.979743 -0.0557064 0.0116795 -0.998379 -0.0560509 0.00989506 -0.998379 0.237824 -0.0419847 -0.9704 0.355182 -0.0744683 -0.931826 0.357378 -0.0630905 -0.931826 0.35255 -0.0860697 -0.931826 0.236362 -0.0495562 -0.9704 0.345868 -0.109887 -0.931826 0.232551 -0.0651371 -0.9704 0.230164 -0.0731265 -0.9704 -0.0552937 0.0134991 -0.998379 0.0963256 -0.0235164 -0.995072 0.606108 -0.0876637 -0.790536 0.603089 -0.106468 -0.790536 0.657203 -0.116021 -0.744731 0.456353 -0.0805632 -0.886144 0.453548 -0.095092 -0.886144 0.660492 -0.0955294 -0.744731 0.663082 -0.0754863 -0.744731 0.608485 -0.0692708 -0.790536 0.541988 -0.0617007 -0.838118 0.710567 -0.0597331 -0.70109 0.708497 -0.0806563 -0.70109 0.74695 -0.0850339 -0.65942 0.749133 -0.0629751 -0.65942 0.711988 -0.039312 -0.70109 -0.196 0.0410938 -0.979743 0.740327 -0.130695 -0.65942 0.744033 -0.107612 -0.65942 0.705729 -0.102072 -0.70109 0.868462 2.56167e-16 -0.495756 0.868194 -0.0236288 -0.495662 0.894517 4.15833e-16 -0.447033 0.844452 1.17246e-16 -0.535631 0.842114 -0.022919 -0.538812 0.867195 -0.0478817 -0.495662 0.81477 -0.0221748 -0.57936 0.820904 1.06052e-17 -0.571067 0.83702 -0.0952876 -0.538812 0.839465 -0.0705688 -0.538812 0.812207 -0.0682774 -0.57936 0.817909 -0.292137 0.495662 0.844319 -0.295444 0.447033 0.827743 -0.262986 0.495662 0.475911 -0.75741 0.447033 0.852274 -0.271644 0.447033 0.859556 -0.247638 0.447033 0.836328 -0.234254 0.495662 0.866163 -0.223434 0.447033 0.872089 -0.199052 0.447033 0.843735 -0.205985 0.495662 0.366723 -0.787295 0.495662 0.365361 -0.8165 0.447033 0.877329 -0.174513 0.447033 0.850034 -0.17822 0.495662 0.85529 -0.15099 0.495662 0.881878 -0.149841 0.447033 0.342316 -0.826427 0.447033 0.885733 -0.12505 0.447033 0.859572 -0.124323 0.495662 0.319003 -0.835702 0.447033 0.483926 -0.375324 0.790536 0.544378 -0.386042 0.744731 0.527347 -0.409 0.744731 0.283468 -0.820954 0.495662 0.384607 -0.645944 0.65942 0.232837 -0.80961 0.538812 0.824499 -0.172866 0.538812 0.29544 -0.84432 0.447033 0.888892 -0.100156 0.447033 0.862942 -0.0982386 0.495662 0.271644 -0.852274 0.447033 0.865463 -0.0727543 0.495662 0.891352 -0.0751875 0.447033 0.240048 -0.834683 0.495662 0.89311 -0.0501622 0.447033 0.189761 -0.820776 0.538812 0.223428 -0.866165 0.447033 0.247633 -0.859558 0.447033 0.195638 -0.846195 0.495662 0.867195 -0.0478817 0.495662 0.199049 -0.87209 0.447033 0.841145 -0.0464434 0.538812 0.868194 -0.0236288 0.495662 0.174511 -0.877329 0.447033 0.894166 -0.0250843 0.447033 0.894517 4.15833e-16 0.447033 0.150408 -0.855393 0.495662 0.1014 -0.836301 0.538812 0.14589 -0.829697 0.538812 0.125043 -0.885734 0.447033 0.149836 -0.881879 0.447033 0.10454 -0.862201 0.495662 0.0564748 -0.840531 0.538812 0.100154 -0.888893 0.447033 0.0751833 -0.891352 0.447033 0.0582238 -0.866562 0.495662 0.0113071 -0.84235 0.538812 0.0501541 -0.89311 0.447033 0.0250867 -0.894165 0.447033 0.0116573 -0.868437 0.495662 -0.0339094 -0.841743 0.538812 -6.66203e-08 -0.894517 0.447033 -0.0349596 -0.867812 0.495662 -0.0250893 -0.894165 0.447033 -0.07898 -0.838716 0.538812 -0.0814259 -0.86469 0.495662 -0.0501575 -0.89311 0.447033 -0.0751852 -0.891352 0.447033 -0.123711 -0.833293 0.538812 -0.100155 -0.888893 0.447033 -0.127542 -0.8591 0.495662 -0.167914 -0.825522 0.538812 -0.125046 -0.885734 0.447033 -0.149839 -0.881878 0.447033 -0.173114 -0.851088 0.495662 -0.211409 -0.815468 0.538812 -0.19905 -0.87209 0.447033 -0.174512 -0.877329 0.447033 -0.254025 -0.803214 0.538812 -0.217956 -0.840723 0.495662 -0.223431 -0.866164 0.447033 -0.247636 -0.859557 0.447033 -0.271644 -0.852274 0.447033 -0.261892 -0.828089 0.495662 -0.286004 -0.763246 0.57936 -0.245777 -0.777133 0.57936 -0.295442 -0.844319 0.447033 -0.304757 -0.813291 0.495662 -0.319006 -0.835701 0.447033 -0.335996 -0.772521 0.538812 -0.346401 -0.796446 0.495662 -0.375075 -0.754321 0.538812 -0.342318 -0.826426 0.447033 -0.365361 -0.8165 0.447033 -0.386691 -0.777682 0.495662 -0.412725 -0.734397 0.538812 -0.388118 -0.805932 0.447033 -0.410569 -0.794729 0.447033 -0.44885 -0.712892 0.538812 -0.425507 -0.757141 0.495662 -0.432696 -0.782902 0.447033 -0.454483 -0.770459 0.447033 -0.462751 -0.73497 0.495662 -0.483368 -0.689954 0.538812 -0.475914 -0.757408 0.447033 -0.496969 -0.743763 0.447033 -0.498338 -0.711322 0.495662 -0.517632 -0.729533 0.447033 -0.532203 -0.686352 0.495662 -0.53789 -0.714728 0.447033 -0.557724 -0.69936 0.447033 -0.499454 -0.644118 0.57936 -0.467673 -0.667551 0.57936 -0.577119 -0.683444 0.447033 -0.576728 -0.614057 0.538812 -0.547346 -0.640386 0.538812 -0.604345 -0.586898 0.538812 -0.614532 -0.650009 0.447033 -0.632521 -0.632518 0.447033 -0.623061 -0.605074 0.495662 -0.650011 -0.61453 0.447033 -0.649711 -0.576364 0.495662 -0.584721 -0.567841 0.57936 -0.609731 -0.540898 0.57936 -0.66699 -0.596058 0.447033 -0.683446 -0.577116 0.447033 -0.674549 -0.547086 0.495662 -0.676641 -0.501835 0.538812 -0.654286 -0.530652 0.538812 -0.699363 -0.557721 0.447033 -0.697597 -0.517376 0.495662 -0.714729 -0.537888 0.447033 -0.729534 -0.517631 0.447033 -0.718887 -0.48736 0.495662 -0.716279 -0.443425 0.538812 -0.697293 -0.472721 0.538812 -0.743765 -0.496965 0.447033 -0.738462 -0.457157 0.495662 -0.757411 -0.47591 0.447033 -0.770459 -0.454482 0.447033 -0.75637 -0.426877 0.495662 -0.709827 -0.400609 0.57936 -0.693021 -0.429027 0.57936 -0.782903 -0.432693 0.447033 -0.772666 -0.396619 0.495662 -0.794731 -0.410565 0.447033 -0.805933 -0.388114 0.447033 -0.78741 -0.366475 0.495662 -0.749456 -0.384705 0.538812 -0.738958 -0.343924 0.57936 -0.72512 -0.372213 0.57936 -0.8165 -0.36536 0.447033 -0.800667 -0.336529 0.495662 -0.826427 -0.342314 0.447033 -0.812503 -0.306853 0.495662 -0.835703 -0.319001 0.447033 -0.798264 -0.269176 0.538812 -0.788096 -0.297635 0.538812 -0.84432 -0.295439 0.447033 -0.822986 -0.277512 0.495662 -0.852274 -0.271643 0.447033 -0.832187 -0.248564 0.495662 -0.859558 -0.24763 0.447033 -0.866165 -0.223426 0.447033 -0.840175 -0.220059 0.495662 -0.814937 -0.213448 0.538812 -0.821575 -0.186269 0.538812 -0.847019 -0.192037 0.495662 -0.87209 -0.199047 0.447033 -0.87733 -0.174509 0.447033 -0.852788 -0.164536 0.495662 -0.881879 -0.149833 0.447033 -0.857549 -0.137585 0.495662 -0.885735 -0.125041 0.447033 -0.861367 -0.111207 0.495662 -0.888893 -0.100154 0.447033 -0.891352 -0.0751809 0.447033 -0.864305 -0.0854208 0.495662 -0.89311 -0.0501505 0.447033 -0.866424 -0.0602411 0.495662 -0.813109 -0.0565342 0.57936 -0.81112 -0.0801644 0.57936 -0.838342 -0.0828548 0.538812 -0.867783 -0.0356775 0.495662 -0.894165 -0.0250844 0.447033 -0.868436 -0.011736 0.495662 -0.894517 8.14756e-08 0.447033 -0.868436 0.0117362 0.495662 -0.894166 0.0250842 0.447033 -0.867783 0.0356773 0.495662 -0.864305 0.0854207 0.495662 -0.857549 0.137585 0.495662 -0.881878 0.149842 0.447033 -0.852788 0.164536 0.495662 -0.888892 0.100156 0.447033 -0.859556 0.247638 0.447033 -0.840175 0.220059 0.495662 -0.866163 0.223434 0.447033 -0.877329 0.174514 0.447033 -0.812503 0.306853 0.495662 -0.844319 0.295444 0.447033 -0.8357 0.319008 0.447033 -0.832187 0.248564 0.495662 -0.794728 0.41057 0.447033 -0.772666 0.396619 0.495662 -0.805931 0.38812 0.447033 -0.8165 0.365361 0.447033 -0.800667 0.336529 0.495662 -0.826425 0.342319 0.447033 -0.770458 0.454483 0.447033 -0.738462 0.457157 0.495662 -0.75637 0.426877 0.495662 -0.782902 0.432696 0.447033 -0.674549 0.547086 0.495662 -0.697597 0.517376 0.495662 -0.69936 0.557725 0.447033 -0.729533 0.517632 0.447033 -0.718887 0.487361 0.495662 -0.743762 0.496969 0.447033 -0.650009 0.614532 0.447033 -0.649711 0.576364 0.495662 -0.66699 0.596059 0.447033 -0.683443 0.577119 0.447033 -0.577116 0.683446 0.447033 -0.564298 0.660218 0.495662 -0.596058 0.66699 0.447033 -0.604345 0.586898 0.538812 -0.558001 0.594118 0.57936 -0.584721 0.567841 0.57936 -0.496965 0.743765 0.447033 -0.462751 0.73497 0.495662 -0.498338 0.711322 0.495662 -0.537888 0.714729 0.447033 -0.532203 0.686352 0.495662 -0.454482 0.770459 0.447033 -0.432694 0.782903 0.447033 -0.425507 0.757141 0.495662 -0.412726 0.734397 0.538812 -0.44885 0.712892 0.538812 -0.36536 0.8165 0.447033 -0.342316 0.826427 0.447033 -0.346401 0.796445 0.495662 -0.388115 0.805933 0.447033 -0.386691 0.777682 0.495662 -0.271644 0.852274 0.447033 -0.261892 0.828089 0.495662 -0.29544 0.84432 0.447033 -0.304757 0.813291 0.495662 -0.319003 0.835702 0.447033 -0.199048 0.87209 0.447033 -0.174511 0.87733 0.447033 -0.173114 0.851088 0.495662 -0.247633 0.859558 0.447033 -0.223428 0.866165 0.447033 -0.217956 0.840723 0.495662 -0.0814258 0.86469 0.495662 -0.127542 0.8591 0.495662 -0.100154 0.888893 0.447033 -0.149836 0.881879 0.447033 -0.0250867 0.894165 0.447033 8.14756e-08 0.894517 0.447033 -0.0349598 0.867812 0.495662 0.0113073 0.84235 0.538812 -0.0339096 0.841743 0.538812 0.0250893 0.894165 0.447033 0.0501576 0.89311 0.447033 0.0582242 0.866562 0.495662 0.0116574 0.868437 0.495662 0.150408 0.855393 0.495662 0.10454 0.862201 0.495662 0.125047 0.885734 0.447033 0.14589 0.829697 0.538812 0.1014 0.836301 0.538812 0.19905 0.87209 0.447033 0.223431 0.866164 0.447033 0.195638 0.846195 0.495662 0.149839 0.881878 0.447033 0.174512 0.877329 0.447033 0.271645 0.852274 0.447033 0.283468 0.820954 0.495662 0.240048 0.834683 0.495662 0.247636 0.859557 0.447033 0.342318 0.826426 0.447033 0.32574 0.805116 0.495662 0.319006 0.835701 0.447033 0.295442 0.844319 0.447033 0.40629 0.767625 0.495662 0.366723 0.787295 0.495662 0.388118 0.805931 0.447033 0.394085 0.744566 0.538812 0.355707 0.763645 0.538812 0.444331 0.74625 0.495662 0.466314 0.701593 0.538812 0.430984 0.723833 0.538812 0.410569 0.794729 0.447033 0.480756 0.723321 0.495662 0.475913 0.757408 0.447033 0.496969 0.743763 0.447033 0.454483 0.770459 0.447033 0.544 0.606964 0.57936 0.514724 0.631982 0.57936 0.531998 0.653192 0.538812 0.500004 0.677995 0.538812 0.467995 0.47577 0.744731 0.448894 0.416589 0.790536 0.429461 0.436595 0.790536 0.524116 0.584779 0.619141 -0.500746 -0.159094 -0.850848 -0.570826 -0.203884 -0.795355 -0.577688 -0.18354 -0.795355 0.339675 0.315229 0.886144 0.324969 0.330368 0.886144 0.382528 0.388883 0.838118 -0.841474 -0.411476 0.350154 -0.870811 -0.425822 0.245689 -0.824744 -0.44406 0.350154 -0.900422 -0.358996 -0.245689 -0.921142 -0.367257 -0.128917 -0.912867 -0.326053 -0.245689 -0.652287 -0.351205 0.671697 -0.702723 -0.378361 0.602514 -0.637705 -0.377034 0.671697 -0.806308 -0.476718 0.350154 -0.853498 -0.459541 0.245689 -0.163356 -0.115843 0.979743 -0.0449761 -0.0348826 0.998379 -0.0464286 -0.0329246 0.998379 -0.604301 -0.428536 0.671697 -0.651027 -0.461671 0.602514 -0.585395 -0.454022 0.671697 0.500048 0.508355 0.70109 0.475924 0.531008 0.70109 0.501754 0.559829 0.65942 -0.152725 -0.129536 0.979743 -0.0417202 -0.0387178 0.998379 -0.0434072 -0.0368166 0.998379 0.53789 0.714728 0.447033 0.548474 0.673421 0.495662 0.515489 0.698992 0.495662 0.517632 0.729533 0.447033 0.596059 0.66699 0.447033 0.57967 0.646763 0.495662 0.577119 0.683444 0.447033 0.557724 0.69936 0.447033 0.632521 0.632518 0.447033 0.609053 0.619172 0.495662 0.614532 0.650009 0.447033 0.66699 0.596058 0.447033 0.636613 0.590798 0.495662 0.650011 0.61453 0.447033 0.699363 0.55772 0.447033 0.662355 0.561787 0.495662 0.683446 0.577116 0.447033 0.714729 0.537888 0.447033 0.686294 0.532277 0.495662 0.729534 0.51763 0.447033 0.708459 0.502399 0.495662 0.728886 0.472275 0.495662 0.706991 0.458089 0.538812 0.757411 0.47591 0.447033 0.747621 0.44202 0.495662 0.743765 0.496965 0.447033 0.782903 0.432693 0.447033 0.764716 0.411739 0.495662 0.725163 0.428742 0.538812 0.741744 0.399371 0.538812 0.717659 0.386403 0.57936 0.756791 0.370067 0.538812 0.780228 0.381528 0.495662 0.794731 0.410564 0.447033 0.805933 0.388114 0.447033 0.794221 0.351473 0.495662 0.757115 0.30186 0.57936 0.782524 0.31199 0.538812 0.76758 0.27416 0.57936 0.8165 0.36536 0.447033 0.826427 0.342314 0.447033 0.806758 0.321653 0.495662 0.835703 0.319001 0.447033 0.817909 0.292137 0.495662 0.827743 0.262986 0.495662 0.844321 0.295438 0.447033 0.852274 0.271643 0.447033 0.836328 0.234253 0.495662 0.859558 0.24763 0.447033 0.802878 0.255086 0.538812 0.784865 0.219839 0.57936 0.776808 0.246803 0.57936 0.866165 0.223426 0.447033 0.843735 0.205985 0.495662 0.81839 0.199797 0.538812 0.824499 0.172866 0.538812 0.797727 0.167253 0.57936 0.87209 0.199047 0.447033 0.85529 0.15099 0.495662 0.850034 0.17822 0.495662 0.87733 0.174509 0.447033 0.881879 0.149833 0.447033 0.829598 0.146455 0.538812 0.859572 0.124323 0.495662 0.885735 0.125041 0.447033 0.862942 0.0982387 0.495662 0.888893 0.100153 0.447033 0.78024 0.0888238 0.619141 0.809841 0.0921936 0.57936 0.78252 0.0657818 0.619141 0.891352 0.0751808 0.447033 0.865463 0.0727543 0.495662 0.89311 0.0501504 0.447033 0.784989 0.0213642 0.619141 0.771317 3.75332e-16 0.636451 0.751497 0.0204527 0.65942 0.894166 0.0250843 0.447033 0.867195 0.0478817 0.495662 0.868194 0.0236287 0.495662 0.868462 5.21812e-16 0.495756 0.844452 3.61835e-16 0.535631 0.770459 0.454482 0.447033 0.687178 0.487307 0.538812 0.664865 0.471484 0.57936 0.665679 0.516288 0.538812 0.61749 0.573051 0.538812 0.642458 0.544912 0.538812 0.590758 0.600572 0.538812 0.562257 0.627334 0.538812 0.474751 0.582904 0.65942 0.450311 0.552895 0.70109 0.177018 0.164279 0.9704 0.266006 0.246862 0.931826 0.184176 0.156212 0.9704 0.25449 0.258718 0.931826 -0.428585 -0.303928 0.850848 -0.440942 -0.285705 0.850848 -0.508696 -0.329605 0.795355 -0.158245 -0.122732 0.979743 -0.26519 -0.188058 0.945679 -0.49444 -0.350628 0.795355 -0.568411 -0.368297 0.735709 -0.256893 -0.199242 0.945679 -0.352916 -0.250268 0.901563 -0.73161 -0.432554 0.52692 -0.669798 -0.43399 0.602514 -0.687014 -0.406187 0.602514 -0.583021 -0.344703 0.735709 -0.521771 -0.30849 0.795355 -0.805225 -0.393751 0.443366 -0.748338 -0.402921 0.52692 -0.763519 -0.373357 0.52692 -0.789215 -0.42493 0.443366 -0.914457 -0.404682 1.91753e-07 -0.906827 -0.401305 -0.128917 -0.906827 -0.401305 0.128917 -0.928893 -0.370347 1.91753e-07 -0.363091 -0.235262 0.901563 -0.886428 -0.392278 0.245689 -0.921142 -0.367257 0.128917 -0.856565 -0.379062 -0.350154 -0.841474 -0.411476 -0.350154 -0.870811 -0.425822 -0.245689 -0.882113 -0.315069 -0.350154 -0.870087 -0.346902 -0.350154 -0.800393 -0.28588 -0.526919 -0.789481 -0.314764 -0.526919 -0.832605 -0.331957 -0.443366 -0.844113 -0.301496 -0.443366 -0.854261 -0.271411 -0.443366 0.0756183 0.0641369 0.995072 -0.415176 -0.322003 0.850848 -0.329949 -0.279852 0.901563 -0.341874 -0.265151 0.901563 -0.810015 -0.257354 -0.526919 -0.751604 -0.268454 -0.602514 -0.760641 -0.241666 -0.602514 0.0783514 0.0607679 0.995072 -0.713371 -0.199813 -0.671697 -0.706047 -0.224321 -0.671697 0.0726795 0.067449 0.995072 -0.652197 -0.182679 -0.735709 -0.645502 -0.205085 -0.735709 -0.657974 -0.160634 -0.735709 -0.58885 -0.143759 -0.795355 0.399838 0.371063 0.838118 0.353409 0.29975 0.886144 -0.420303 -0.102611 -0.901563 -0.42344 -0.0887794 -0.901563 -0.318184 -0.0667112 -0.945679 -0.510421 -0.124611 -0.850848 -0.58368 -0.163487 -0.795355 -0.195999 -0.0410937 -0.979743 -0.315827 -0.0771043 -0.945679 -0.0542456 -0.0172346 -0.998379 -0.0548083 -0.0153516 -0.998379 0.0954803 0.0267438 -0.995072 0.0976452 0.017238 -0.995072 -0.0557064 -0.0116795 -0.998379 -0.0560509 -0.00989506 -0.998379 0.097045 0.0203467 -0.995072 0.237824 0.0419847 -0.9704 0.636035 0.202078 -0.744731 0.686646 0.192328 -0.70109 0.679597 0.215918 -0.70109 0.359168 0.0519477 -0.931826 0.239014 0.0345695 -0.9704 0.360576 0.0410486 -0.931826 0.608485 0.0692709 -0.790537 0.541988 0.0617008 -0.838118 0.610262 0.0513011 -0.790537 0.539871 0.0780834 -0.838118 0.458637 0.0663343 -0.886144 0.710566 0.0597331 -0.70109 0.708496 0.0806564 -0.70109 0.663082 0.0754864 -0.744731 0.665019 0.0559042 -0.744731 0.771327 8.81105e-17 -0.63644 0.784989 0.0213642 -0.619141 0.751497 0.0204527 -0.65942 0.749133 0.0629751 -0.65942 0.809841 0.0921936 -0.57936 0.812207 0.0682774 -0.57936 0.839465 0.0705689 -0.538812 0.81477 0.0221747 -0.57936 0.796815 3.4965e-16 -0.604223 0.89311 0.0501621 -0.447033 0.867195 0.0478817 -0.495662 0.894166 0.0250843 -0.447033 0.841145 0.0464433 -0.538812 0.842114 0.0229189 -0.538812 0.868194 0.0236287 -0.495662 0.432696 0.782902 0.447033 0.460435 0.0524167 -0.886144 -0.194547 -0.0474957 -0.979743 -0.50594 -0.141712 -0.850848 0.364074 0.406212 0.838118 0.408742 0.456051 0.790536 0.445417 0.496971 0.744731 0.421446 0.517455 0.744731 -0.0751835 0.891352 0.447033 -0.0501543 0.89311 0.447033 0.365361 0.8165 0.447033 0.266025 0.770437 0.57936 0.225277 0.783321 0.57936 0.232837 0.80961 0.538812 0.315955 0.780931 0.538812 0.189761 0.820776 0.538812 0.0751854 0.891352 0.447033 0.100155 0.888893 0.447033 0.0564751 0.840531 0.538812 -0.125044 0.885734 0.447033 -0.0789798 0.838716 0.538812 -0.123711 0.833293 0.538812 -0.162462 0.798717 0.57936 -0.204545 0.788989 0.57936 -0.211409 0.815468 0.538812 -0.254025 0.803214 0.538812 -0.295602 0.788861 0.538812 -0.335996 0.772521 0.538812 -0.399324 0.710551 0.57936 -0.362896 0.729828 0.57936 -0.410565 0.794731 0.447033 -0.475911 0.75741 0.447033 -0.517631 0.729534 0.447033 -0.632518 0.632521 0.447033 -0.623061 0.605074 0.495662 -0.483368 0.689954 0.538812 -0.557721 0.699363 0.447033 -0.594589 0.633074 0.495662 -0.61453 0.650011 0.447033 -0.516216 0.665735 0.538812 -0.547347 0.640385 0.538812 -0.654286 0.530652 0.538812 -0.609731 0.540897 0.57936 -0.633041 0.513422 0.57936 -0.714728 0.53789 0.447033 -0.697293 0.472721 0.538812 -0.676641 0.501835 0.538812 -0.757408 0.475915 0.447033 -0.716279 0.443425 0.538812 -0.733649 0.414054 0.538812 -0.78741 0.366475 0.495662 -0.788096 0.297635 0.538812 -0.776616 0.32642 0.538812 -0.822986 0.277512 0.495662 -0.852274 0.271645 0.447033 -0.847019 0.192038 0.495662 -0.861367 0.111207 0.495662 -0.872089 0.199052 0.447033 -0.885733 0.12505 0.447033 0.820904 1.32565e-16 0.571067 0.842114 0.0229189 0.538812 0.678158 -1.17774e-16 0.734916 0.712809 0.0193997 0.70109 0.712911 7.4781e-17 0.701254 0.81477 0.0221747 0.57936 0.841145 0.0464433 0.538812 0.839465 0.0705689 0.538812 0.83702 0.0952877 0.538812 0.833751 0.120588 0.538812 0.74695 0.0850341 0.65942 0.744033 0.107612 0.65942 0.777193 0.112408 0.619141 0.811206 0.227217 0.538812 0.79334 0.283361 0.538812 0.770363 0.340915 0.538812 0.745349 0.329845 0.57936 0.729441 0.290826 0.619141 0.718105 0.317789 0.619141 0.684035 0.443214 0.57936 0.701617 0.414821 0.57936 0.675971 0.399658 0.619141 0.621597 0.527218 0.57936 0.620522 0.481266 0.619141 0.598877 0.507947 0.619141 0.59744 0.554444 0.57936 0.571575 0.581071 0.57936 0.451173 0.678812 0.57936 0.41699 0.70033 0.57936 0.381289 0.720389 0.57936 0.344157 0.738849 0.57936 0.294522 0.727956 0.619141 0.256301 0.742276 0.619141 0.274953 0.796293 0.538812 0.1836 0.794124 0.57936 0.141153 0.802757 0.57936 0.0981072 0.809146 0.57936 0.0546414 0.813238 0.57936 0.0109401 0.814998 0.57936 -0.0328085 0.814411 0.57936 -0.0764153 0.811482 0.57936 -0.115319 0.776766 0.619141 -0.156524 0.769522 0.619141 -0.167914 0.825522 0.538812 -0.245777 0.777133 0.57936 -0.286004 0.763246 0.57936 -0.325086 0.747437 0.57936 -0.375075 0.754321 0.538812 -0.434276 0.689744 0.57936 -0.499454 0.644118 0.57936 -0.450579 0.643151 0.619141 -0.481198 0.620574 0.619141 -0.529574 0.619592 0.57936 -0.576728 0.614057 0.538812 -0.630194 0.55905 0.538812 -0.65467 0.48554 0.57936 -0.674651 0.457371 0.57936 -0.72512 0.372213 0.57936 -0.683882 0.385966 0.619141 -0.698616 0.358608 0.619141 -0.749456 0.384705 0.538812 -0.763757 0.355467 0.538812 -0.751398 0.315821 0.57936 -0.762506 0.287971 0.57936 -0.798265 0.269176 0.538812 -0.807189 0.241097 0.538812 -0.814937 0.213448 0.538812 -0.821575 0.186269 0.538812 -0.827171 0.159594 0.538812 -0.831789 0.133452 0.538812 -0.835492 0.107866 0.538812 -0.838342 0.0828548 0.538812 -0.840397 0.0584315 0.538812 -0.841715 0.0346056 0.538812 -0.842349 0.0113837 0.538812 -0.842349 -0.0113835 0.538812 -0.841715 -0.0346058 0.538812 -0.840397 -0.0584315 0.538812 -0.835492 -0.107866 0.538812 -0.831789 -0.133452 0.538812 -0.827171 -0.159594 0.538812 -0.794898 -0.18022 0.57936 -0.788475 -0.206517 0.57936 -0.807189 -0.241098 0.538812 -0.772344 -0.260436 0.57936 -0.762506 -0.287971 0.57936 -0.776616 -0.32642 0.538812 -0.763757 -0.355467 0.538812 -0.733649 -0.414054 0.538812 -0.65467 -0.48554 0.57936 -0.649991 -0.440653 0.619141 -0.630741 -0.467793 0.619141 -0.633041 -0.513422 0.57936 -0.630194 -0.55905 0.538812 -0.558002 -0.594118 0.57936 -0.529574 -0.619592 0.57936 -0.516216 -0.665735 0.538812 -0.434276 -0.689744 0.57936 -0.399324 -0.710551 0.57936 -0.362896 -0.729828 0.57936 -0.313203 -0.720117 0.619141 -0.27555 -0.735348 0.619141 -0.295602 -0.788861 0.538812 -0.204544 -0.788989 0.57936 -0.162462 -0.798717 0.57936 -0.119694 -0.806235 0.57936 -0.0764154 -0.811482 0.57936 -0.0328084 -0.814411 0.57936 0.01094 -0.814999 0.57936 0.0546411 -0.813238 0.57936 0.0981071 -0.809146 0.57936 0.135994 -0.773414 0.619141 0.176889 -0.765098 0.619141 0.1836 -0.794124 0.57936 0.225277 -0.783321 0.57936 0.394085 -0.744566 0.538812 0.430984 -0.723833 0.538812 0.466314 -0.701593 0.538812 0.500004 -0.677995 0.538812 0.531998 -0.653192 0.538812 0.562257 -0.627334 0.538812 0.590758 -0.600572 0.538812 0.61749 -0.573051 0.538812 0.642459 -0.544912 0.538812 0.665679 -0.516288 0.538812 0.687178 -0.487307 0.538812 0.544001 -0.606964 0.57936 0.571575 -0.581071 0.57936 0.725163 -0.428743 0.538812 0.706991 -0.458089 0.538812 0.741744 -0.399371 0.538812 0.756791 -0.370067 0.538812 0.770363 -0.340915 0.538812 0.782524 -0.31199 0.538812 0.701617 -0.414821 0.57936 0.79334 -0.283361 0.538812 0.802878 -0.255086 0.538812 0.811205 -0.227217 0.538812 0.81839 -0.199797 0.538812 0.776808 -0.246803 0.57936 0.76758 -0.27416 0.57936 0.829598 -0.146455 0.538812 0.833751 -0.120588 0.538812 0.83702 -0.0952876 0.538812 0.80266 -0.141699 0.57936 0.839465 -0.0705688 0.538812 0.842114 -0.022919 0.538812 0.796809 2.20951e-17 0.604231 0.813832 0.0449353 0.57936 0.812207 0.0682774 0.57936 0.806678 0.116673 0.57936 0.80266 0.141699 0.57936 0.740327 0.130695 0.65942 0.702214 0.123967 0.70109 0.735777 0.154265 0.65942 0.791817 0.19331 0.57936 0.756177 0.211803 0.619141 0.762874 0.186244 0.619141 0.730326 0.178298 0.65942 0.707971 0.252869 0.65942 0.739523 0.264139 0.619141 0.716482 0.227637 0.65942 0.732217 0.35805 0.57936 0.691428 0.372279 0.619141 0.705454 0.344963 0.619141 0.675355 0.330245 0.65942 0.659032 0.427014 0.619141 0.630914 0.408795 0.65942 0.640563 0.454251 0.619141 0.644064 0.499524 0.57936 0.575602 0.534178 0.619141 0.573325 0.486275 0.65942 0.551044 0.511387 0.65942 0.550683 0.559832 0.619141 0.434682 0.654 0.619141 0.401748 0.674732 0.619141 0.367352 0.694058 0.619141 0.31743 0.681472 0.65942 0.281956 0.696898 0.65942 0.305696 0.755574 0.57936 0.217043 0.75469 0.619141 0.176889 0.765098 0.619141 0.135993 0.773414 0.619141 0.0945212 0.77957 0.619141 0.0526441 0.783513 0.619141 0.0105402 0.785209 0.619141 -0.0316093 0.784643 0.619141 -0.070481 0.748464 0.65942 -0.110399 0.743625 0.65942 -0.119694 0.806235 0.57936 -0.197068 0.76015 0.619141 -0.236793 0.748728 0.619141 -0.27555 0.735348 0.619141 -0.29984 0.689392 0.65942 -0.334714 0.673151 0.65942 -0.349631 0.703151 0.619141 -0.384728 0.684579 0.619141 -0.418402 0.664533 0.619141 -0.467673 0.667551 0.57936 -0.510217 0.596944 0.619141 -0.537606 0.572402 0.619141 -0.563349 0.547085 0.619141 -0.587445 0.521127 0.619141 -0.609902 0.494655 0.619141 -0.630741 0.467793 0.619141 -0.649991 0.440653 0.619141 -0.693021 0.429026 0.57936 -0.709827 0.400609 0.57936 -0.738957 0.343925 0.57936 -0.744114 0.250916 0.619141 -0.703291 0.265607 0.65942 -0.712365 0.24021 0.65942 -0.772344 0.260435 0.57936 -0.780979 0.233269 0.57936 -0.788475 0.206517 0.57936 -0.794898 0.180221 0.57936 -0.800312 0.154412 0.57936 -0.80478 0.129119 0.57936 -0.808363 0.104364 0.57936 -0.81112 0.0801644 0.57936 -0.813109 0.0565341 0.57936 -0.814384 0.0334819 0.57936 -0.814997 0.011014 0.57936 -0.814997 -0.0110139 0.57936 -0.814384 -0.0334821 0.57936 -0.778816 -0.100549 0.619141 -0.74813 -0.073939 0.65942 -0.745587 -0.0962589 0.65942 -0.808363 -0.104364 0.57936 -0.80478 -0.129119 0.57936 -0.800312 -0.154412 0.57936 -0.752433 -0.224743 0.619141 -0.727243 -0.19048 0.65942 -0.720329 -0.215154 0.65942 -0.780979 -0.233269 0.57936 -0.703291 -0.265607 0.65942 -0.693046 -0.291295 0.65942 -0.723934 -0.304277 0.619141 -0.751398 -0.315821 0.57936 -0.711947 -0.331353 0.619141 -0.698616 -0.358608 0.619141 -0.683882 -0.385966 0.619141 -0.66769 -0.413345 0.619141 -0.674651 -0.457371 0.57936 -0.609902 -0.494655 0.619141 -0.587444 -0.521127 0.619141 -0.563349 -0.547085 0.619141 -0.537606 -0.572402 0.619141 -0.488448 -0.571475 0.65942 -0.460668 -0.594097 0.65942 -0.481198 -0.620574 0.619141 -0.450579 -0.643151 0.619141 -0.418402 -0.664533 0.619141 -0.384728 -0.684579 0.619141 -0.349631 -0.703151 0.619141 -0.325086 -0.747437 0.57936 -0.236793 -0.748728 0.619141 -0.197068 -0.76015 0.619141 -0.156524 -0.769522 0.619141 -0.115319 -0.776766 0.619141 -0.0736223 -0.781821 0.619141 -0.0316092 -0.784643 0.619141 0.0105401 -0.785209 0.619141 0.0526438 -0.783513 0.619141 0.0904883 -0.746309 0.65942 0.130191 -0.740416 0.65942 0.141153 -0.802757 0.57936 0.217043 -0.75469 0.619141 0.256301 -0.742276 0.619141 0.381289 -0.720389 0.57936 0.41699 -0.70033 0.57936 0.451173 -0.678812 0.57936 0.483769 -0.65598 0.57936 0.514724 -0.631982 0.57936 0.560074 -0.362895 0.744731 0.57447 -0.339647 0.744731 0.613815 -0.36291 0.70109 0.59744 -0.554444 0.57936 0.621598 -0.527218 0.57936 0.644064 -0.499524 0.57936 0.664865 -0.471484 0.57936 0.524116 -0.584779 0.619141 0.684035 -0.443214 0.57936 0.717659 -0.386403 0.57936 0.732217 -0.35805 0.57936 0.745349 -0.329845 0.57936 0.757115 -0.30186 0.57936 0.675971 -0.399659 0.619141 0.784865 -0.219839 0.57936 0.791817 -0.19331 0.57936 0.748414 -0.237782 0.619141 0.739523 -0.264139 0.619141 0.797727 -0.167253 0.57936 0.806678 -0.116673 0.57936 0.809841 -0.0921935 0.57936 0.812207 -0.0682774 0.57936 0.78024 -0.0888237 0.619141 0.78252 -0.0657817 0.619141 0.81477 -0.0221748 0.57936 0.813832 -0.0449353 0.57936 0.470979 -2.79194e-17 0.882144 0.463238 0.0126075 0.886144 0.536527 2.22653e-16 0.843883 0.784085 0.0432928 0.619141 0.612188 0.0166613 0.790536 0.591571 -2.48107e-17 0.806253 0.545287 0.0148405 0.838118 0.773322 0.13652 0.619141 0.768569 0.16114 0.619141 0.748414 0.237782 0.619141 0.698319 0.278418 0.65942 0.671524 0.239851 0.70109 0.662368 0.264085 0.70109 0.64713 0.382607 0.65942 0.661927 0.356396 0.65942 0.627851 0.338048 0.70109 0.613232 0.43487 0.65942 0.527188 0.535946 0.65942 0.522675 0.48506 0.70109 0.4462 0.605038 0.65942 0.416136 0.626096 0.65942 0.384607 0.645943 0.65942 0.333574 0.630239 0.70109 0.301089 0.646389 0.70109 0.331577 0.711843 0.619141 0.245366 0.710606 0.65942 0.207782 0.72249 0.65942 0.169342 0.732454 0.65942 0.130191 0.740416 0.65942 0.0904884 0.746309 0.65942 0.050398 0.750084 0.65942 0.0100905 0.751707 0.65942 -0.0287028 0.712495 0.70109 -0.0668526 0.709932 0.70109 -0.0736222 0.781821 0.619141 -0.149845 0.73669 0.65942 -0.18866 0.727718 0.65942 -0.22669 0.716783 0.65942 -0.263793 0.703974 0.65942 -0.313203 0.720117 0.619141 -0.368313 0.655371 0.65942 -0.400551 0.63618 0.65942 -0.431354 0.61571 0.65942 -0.460667 0.594097 0.65942 -0.488448 0.571475 0.65942 -0.514668 0.54798 0.65942 -0.539313 0.523743 0.65942 -0.562381 0.498892 0.65942 -0.58388 0.47355 0.65942 -0.60383 0.447834 0.65942 -0.622259 0.421852 0.65942 -0.66769 0.413345 0.619141 -0.654703 0.369499 0.65942 -0.668809 0.343308 0.65942 -0.711947 0.331354 0.619141 -0.723934 0.304277 0.619141 -0.734635 0.277445 0.619141 -0.752433 0.224743 0.619141 -0.759655 0.198969 0.619141 -0.765843 0.173633 0.619141 -0.771059 0.148768 0.619141 -0.775364 0.124399 0.619141 -0.778816 0.100549 0.619141 -0.781472 0.0772343 0.619141 -0.783388 0.0544677 0.619141 -0.784617 0.0322581 0.619141 -0.785208 0.0106114 0.619141 -0.785208 -0.0106113 0.619141 -0.784617 -0.0322583 0.619141 -0.783388 -0.0544677 0.619141 -0.781472 -0.0772343 0.619141 -0.775364 -0.124399 0.619141 -0.771059 -0.148768 0.619141 -0.765843 -0.173633 0.619141 -0.759655 -0.198969 0.619141 -0.744114 -0.250916 0.619141 -0.734635 -0.277445 0.619141 -0.681571 -0.317216 0.65942 -0.668809 -0.343308 0.65942 -0.654703 -0.369499 0.65942 -0.639203 -0.395709 0.65942 -0.622259 -0.421852 0.65942 -0.60383 -0.447834 0.65942 -0.58388 -0.47355 0.65942 -0.562381 -0.498892 0.65942 -0.539313 -0.523743 0.65942 -0.514668 -0.54798 0.65942 -0.510217 -0.596945 0.619141 -0.431354 -0.61571 0.65942 -0.400551 -0.63618 0.65942 -0.368313 -0.655371 0.65942 -0.317483 -0.638496 0.70109 -0.284404 -0.653901 0.70109 -0.29984 -0.689392 0.65942 -0.263793 -0.703973 0.65942 -0.22669 -0.716783 0.65942 -0.18866 -0.727718 0.65942 -0.149845 -0.73669 0.65942 -0.110399 -0.743625 0.65942 -0.0704812 -0.748464 0.65942 -0.0302605 -0.751166 0.65942 0.0100904 -0.751707 0.65942 0.0478032 -0.711469 0.70109 0.0858298 -0.707888 0.70109 0.0945211 -0.77957 0.619141 0.169342 -0.732454 0.65942 0.207782 -0.72249 0.65942 0.245366 -0.710606 0.65942 0.267441 -0.66102 0.70109 0.401748 -0.674732 0.619141 0.434682 -0.654 0.619141 0.466086 -0.632003 0.619141 0.49591 -0.608882 0.619141 0.281957 -0.696897 0.65942 0.575603 -0.534178 0.619141 0.598877 -0.507947 0.619141 0.620522 -0.481265 0.619141 0.640563 -0.454251 0.619141 0.675355 -0.330245 0.65942 0.705454 -0.344963 0.619141 0.661927 -0.356396 0.65942 0.659032 -0.427014 0.619141 0.691428 -0.372279 0.619141 0.718105 -0.317789 0.619141 0.729441 -0.290826 0.619141 0.64713 -0.382607 0.65942 0.756177 -0.211803 0.619141 0.762874 -0.186244 0.619141 0.768569 -0.16114 0.619141 0.773322 -0.13652 0.619141 0.777193 -0.112408 0.619141 0.740327 -0.130695 0.65942 0.74695 -0.0850339 0.65942 0.749133 -0.0629751 0.65942 0.784989 -0.0213643 0.619141 0.784085 -0.0432929 0.619141 0.743636 2.36559e-17 0.668584 0.750632 0.0414457 0.65942 0.749133 0.0629751 0.65942 0.663082 0.0754864 0.744731 0.610263 0.0513012 0.790536 0.608485 0.0692709 0.790536 0.599383 0.125668 0.790536 0.648324 0.158278 0.744731 0.653163 0.136944 0.744731 0.723914 0.202766 0.65942 0.636035 0.202078 0.744731 0.679597 0.215918 0.70109 0.642632 0.18 0.744731 0.687466 0.30423 0.65942 0.652075 0.288568 0.70109 0.619911 0.247157 0.744731 0.610277 0.270071 0.744731 0.613815 0.36291 0.70109 0.598434 0.38775 0.70109 0.560074 0.362895 0.744731 0.581663 0.412482 0.70109 0.594047 0.460732 0.65942 0.563465 0.437013 0.70109 0.54381 0.461241 0.70109 0.423229 0.57389 0.70109 0.394713 0.593864 0.70109 0.364807 0.61269 0.70109 0.351679 0.664445 0.65942 0.267441 0.66102 0.70109 0.232734 0.674023 0.70109 0.197085 0.685296 0.70109 0.160624 0.694746 0.70109 0.123489 0.702299 0.70109 0.08583 0.707888 0.70109 0.0478035 0.711469 0.70109 0.00895755 0.667305 0.744731 -0.026863 0.666824 0.744731 -0.0302607 0.751166 0.65942 -0.104715 0.705342 0.70109 -0.142131 0.698764 0.70109 -0.178948 0.690254 0.70109 -0.21502 0.679882 0.70109 -0.234174 0.624931 0.744731 -0.266174 0.611987 0.744731 -0.284404 0.653901 0.70109 -0.317483 0.638496 0.70109 -0.349352 0.621632 0.70109 -0.355577 0.564749 0.744731 -0.382922 0.546578 0.744731 -0.409148 0.584013 0.70109 -0.436952 0.563512 0.70109 -0.433605 0.507309 0.744731 -0.456881 0.486453 0.744731 -0.488172 0.51977 0.70109 -0.511549 0.49678 0.70109 -0.533429 0.473209 0.70109 -0.553821 0.449171 0.70109 -0.606296 0.375338 0.70109 -0.552391 0.374487 0.744731 -0.567432 0.351279 0.744731 -0.639203 0.395709 0.65942 -0.620998 0.350476 0.70109 -0.634378 0.325634 0.70109 -0.681571 0.317216 0.65942 -0.693046 0.291295 0.65942 -0.667085 0.251934 0.70109 -0.675692 0.227844 0.70109 -0.720329 0.215154 0.65942 -0.727243 0.19048 0.65942 -0.733168 0.166225 0.65942 -0.738161 0.14242 0.65942 -0.742282 0.119092 0.65942 -0.745587 0.0962591 0.65942 -0.74813 0.073939 0.65942 -0.749964 0.0521438 0.65942 -0.75114 0.0308818 0.65942 -0.751706 0.0101587 0.65942 -0.751706 -0.0101586 0.65942 -0.75114 -0.030882 0.65942 -0.749964 -0.0521438 0.65942 -0.704069 -0.112961 0.70109 -0.661872 -0.0854509 0.744731 -0.658938 -0.10572 0.744731 -0.742282 -0.119092 0.65942 -0.738161 -0.14242 0.65942 -0.733168 -0.166225 0.65942 -0.689804 -0.180674 0.70109 -0.683246 -0.204077 0.70109 -0.712365 -0.240211 0.65942 -0.667085 -0.251934 0.70109 -0.657367 -0.276298 0.70109 -0.646483 -0.300885 0.70109 -0.634378 -0.325634 0.70109 -0.620998 -0.350476 0.70109 -0.606296 -0.375338 0.70109 -0.590224 -0.400135 0.70109 -0.572744 -0.424779 0.70109 -0.518321 -0.42038 0.744731 -0.499236 -0.442876 0.744731 -0.533429 -0.473209 0.70109 -0.511549 -0.49678 0.70109 -0.456881 -0.486452 0.744731 -0.433605 -0.50731 0.744731 -0.463302 -0.542055 0.70109 -0.436952 -0.563512 0.70109 -0.409148 -0.584013 0.70109 -0.37993 -0.603428 0.70109 -0.326959 -0.581785 0.744731 -0.297132 -0.597569 0.744731 -0.334714 -0.673151 0.65942 -0.250213 -0.667732 0.70109 -0.21502 -0.679882 0.70109 -0.178948 -0.690254 0.70109 -0.142131 -0.698764 0.70109 -0.104715 -0.705342 0.70109 -0.0668527 -0.709932 0.70109 -0.0268628 -0.666824 0.744731 0.00895744 -0.667305 0.744731 0.00957093 -0.713008 0.70109 0.044739 -0.665864 0.744731 0.0503977 -0.750084 0.65942 0.123489 -0.702298 0.70109 0.160624 -0.694746 0.70109 0.197085 -0.685296 0.70109 0.232734 -0.674023 0.70109 0.416135 -0.626096 0.65942 0.4462 -0.605038 0.65942 0.474752 -0.582904 0.65942 0.551044 -0.511387 0.65942 0.573325 -0.486275 0.65942 0.594047 -0.460732 0.65942 0.613232 -0.43487 0.65942 0.500048 -0.508355 0.70109 0.475924 -0.531008 0.70109 0.630914 -0.408795 0.65942 0.687466 -0.30423 0.65942 0.698319 -0.278418 0.65942 0.707971 -0.252869 0.65942 0.716482 -0.227637 0.65942 0.723914 -0.202767 0.65942 0.730326 -0.178298 0.65942 0.671524 -0.239851 0.70109 0.679597 -0.215918 0.70109 0.735777 -0.154265 0.65942 0.744033 -0.107612 0.65942 0.702214 -0.123967 0.70109 0.708496 -0.0806563 0.70109 0.710566 -0.0597331 0.70109 0.751497 -0.0204528 0.65942 0.750632 -0.0414457 0.65942 0.667118 0.0181562 0.744731 0.711988 0.039312 0.70109 0.710566 0.0597331 0.70109 0.708496 0.0806564 0.70109 0.705729 0.102072 0.70109 0.541988 0.0617008 0.838118 0.539871 0.0780834 0.838118 0.606108 0.0876635 0.790536 0.697898 0.146323 0.70109 0.692728 0.169119 0.70109 0.686646 0.192328 0.70109 0.576731 0.205994 0.790536 0.628479 0.224477 0.744731 0.583665 0.185439 0.790536 0.640587 0.313243 0.70109 0.599525 0.293165 0.744731 0.57447 0.339647 0.744731 0.587606 0.316379 0.744731 0.539223 0.290329 0.790536 0.544378 0.386042 0.744731 0.499555 0.354256 0.790536 0.527347 0.409 0.744731 0.489172 0.453968 0.744731 0.467045 0.396132 0.790536 0.3961 0.537104 0.744731 0.369412 0.555798 0.744731 0.313311 0.526202 0.790536 0.286487 0.541274 0.790536 0.312192 0.589841 0.744731 0.281789 0.604955 0.744731 0.250298 0.618649 0.744731 0.217816 0.630819 0.744731 0.184452 0.641368 0.744731 0.150328 0.650214 0.744731 0.115573 0.657281 0.744731 0.0737142 0.607962 0.790536 0.0410555 0.611037 0.790536 0.0447393 0.665864 0.744731 0.00822 0.61236 0.790536 0.00957105 0.713008 0.70109 -0.0625674 0.664426 0.744731 -0.098003 0.66013 0.744731 -0.133021 0.653974 0.744731 -0.167477 0.646009 0.744731 -0.201237 0.636302 0.744731 -0.250213 0.667732 0.70109 -0.297132 0.597569 0.744731 -0.326959 0.581785 0.744731 -0.37993 0.603428 0.70109 -0.408943 0.527391 0.744731 -0.463302 0.542055 0.70109 -0.499236 0.442876 0.744731 -0.439338 0.426655 0.790536 -0.45813 0.40641 0.790536 -0.518321 0.42038 0.744731 -0.572744 0.424779 0.70109 -0.590224 0.400135 0.70109 -0.605044 0.281599 0.744731 -0.544829 0.279667 0.790536 -0.555225 0.258412 0.790536 -0.646483 0.300885 0.70109 -0.657367 0.276298 0.70109 -0.63945 0.190996 0.744731 -0.580311 0.195681 0.790536 -0.586799 0.17527 0.790536 -0.683246 0.204077 0.70109 -0.689804 0.180674 0.70109 -0.695423 0.157668 0.70109 -0.70016 0.135088 0.70109 -0.704069 0.112961 0.70109 -0.707203 0.0913036 0.70109 -0.709615 0.0701325 0.70109 -0.711355 0.0494594 0.70109 -0.712471 0.029292 0.70109 -0.713008 0.00963571 0.70109 -0.713008 -0.00963558 0.70109 -0.712471 -0.0292921 0.70109 -0.711355 -0.0494594 0.70109 -0.709615 -0.0701325 0.70109 -0.707203 -0.0913034 0.70109 -0.70016 -0.135088 0.70109 -0.695423 -0.157667 0.70109 -0.645588 -0.169092 0.744731 -0.63945 -0.190996 0.744731 -0.675692 -0.227844 0.70109 -0.624325 -0.235785 0.744731 -0.61523 -0.258588 0.744731 -0.605044 -0.281599 0.744731 -0.593714 -0.304761 0.744731 -0.581193 -0.328011 0.744731 -0.567432 -0.351279 0.744731 -0.552391 -0.374486 0.744731 -0.536031 -0.397551 0.744731 -0.553821 -0.449171 0.70109 -0.478759 -0.464937 0.744731 -0.488173 -0.519769 0.70109 -0.408943 -0.527391 0.744731 -0.382922 -0.546578 0.744731 -0.326299 -0.518248 0.790536 -0.300037 -0.533882 0.790536 -0.349352 -0.621632 0.70109 -0.266174 -0.611987 0.744731 -0.234175 -0.624931 0.744731 -0.201237 -0.636302 0.744731 -0.167477 -0.646009 0.744731 -0.133021 -0.653974 0.744731 -0.098003 -0.66013 0.744731 -0.0574157 -0.609718 0.790536 -0.024651 -0.611919 0.790536 -0.0287027 -0.712495 0.70109 0.0803282 -0.662513 0.744731 0.115573 -0.657281 0.744731 0.150328 -0.650213 0.744731 0.184452 -0.641368 0.744731 0.250298 -0.618649 0.744731 0.199881 -0.578878 0.790536 0.229689 -0.56771 0.790536 0.281789 -0.604955 0.744731 0.394712 -0.593864 0.70109 0.423229 -0.57389 0.70109 0.450311 -0.552895 0.70109 0.522676 -0.48506 0.70109 0.54381 -0.461241 0.70109 0.563465 -0.437013 0.70109 0.581663 -0.412482 0.70109 0.445417 -0.496971 0.744731 0.467995 -0.47577 0.744731 0.598434 -0.38775 0.70109 0.62785 -0.338048 0.70109 0.640587 -0.313243 0.70109 0.652075 -0.288568 0.70109 0.662368 -0.264085 0.70109 0.686646 -0.192328 0.70109 0.692728 -0.169119 0.70109 0.636035 -0.202078 0.744731 0.628479 -0.224477 0.744731 0.697899 -0.146323 0.70109 0.705729 -0.102072 0.70109 0.657203 -0.116021 0.744731 0.663082 -0.0754863 0.744731 0.665019 -0.0559042 0.744731 0.711988 -0.039312 0.70109 0.712809 -0.0193998 0.70109 0.638195 3.39784e-17 0.769875 0.66635 0.0367921 0.744731 0.665019 0.0559042 0.744731 0.660492 0.0955293 0.744731 0.657203 0.116021 0.744731 0.589719 0.165179 0.790536 0.594942 0.145246 0.790536 0.529925 0.129373 0.838118 0.568868 0.226806 0.790536 0.560027 0.247833 0.790536 0.506701 0.20202 0.838118 0.498826 0.220749 0.838118 0.513958 0.333015 0.790536 0.527169 0.311681 0.790536 0.469558 0.27762 0.838118 0.508952 0.431676 0.744731 0.386745 0.474848 0.790536 0.363486 0.492879 0.790536 0.301948 0.454296 0.838118 0.279071 0.468697 0.838118 0.341423 0.573416 0.744731 0.258587 0.555144 0.790536 0.229689 0.56771 0.790536 0.199881 0.578878 0.790536 0.169265 0.588559 0.790536 0.13795 0.596676 0.790536 0.0656585 0.541523 0.838118 0.0944668 0.537247 0.838118 0.0803283 0.662513 0.744731 -0.0246511 0.611919 0.790536 -0.0574156 0.609718 0.790536 -0.0899336 0.605776 0.790536 -0.122068 0.600126 0.790536 -0.153687 0.592817 0.790536 -0.214893 0.573475 0.790536 -0.164487 0.520098 0.838118 -0.191409 0.510804 0.838118 -0.244257 0.561596 0.790536 -0.272667 0.548366 0.790536 -0.300037 0.533882 0.790536 -0.326299 0.518248 0.790536 -0.351392 0.501573 0.790536 -0.375271 0.483966 0.790536 -0.397902 0.465538 0.790536 -0.419262 0.446399 0.790536 -0.478759 0.464937 0.744731 -0.491895 0.364817 0.790536 -0.423664 0.343609 0.838118 -0.43814 0.324949 0.838118 -0.536031 0.397551 0.744731 -0.506908 0.343652 0.790536 -0.520711 0.322355 0.790536 -0.581193 0.328011 0.744731 -0.593714 0.304761 0.744731 -0.61523 0.258588 0.744731 -0.624325 0.235785 0.744731 -0.63238 0.213239 0.744731 -0.645588 0.169092 0.744731 -0.650847 0.147561 0.744731 -0.65528 0.126429 0.744731 -0.658938 0.10572 0.744731 -0.661872 0.085451 0.744731 -0.664129 0.0656371 0.744731 -0.665758 0.0462891 0.744731 -0.666802 0.0274144 0.744731 -0.667304 0.00901807 0.744731 -0.667304 -0.00901795 0.744731 -0.666802 -0.0274145 0.744731 -0.665758 -0.0462891 0.744731 -0.664129 -0.0656371 0.744731 -0.601325 -0.116019 0.790536 -0.538601 -0.086413 0.838118 -0.535611 -0.10334 0.838118 -0.65528 -0.126429 0.744731 -0.650847 -0.147561 0.744731 -0.580311 -0.195682 0.790536 -0.522672 -0.156116 0.838118 -0.516893 -0.174297 0.838118 -0.63238 -0.21324 0.744731 -0.572919 -0.21637 0.790536 -0.564573 -0.237296 0.790536 -0.533338 -0.301003 0.790536 -0.485288 -0.249105 0.838118 -0.475053 -0.268109 0.838118 -0.506908 -0.343652 0.790536 -0.463806 -0.287127 0.838118 -0.451512 -0.306097 0.838118 -0.491895 -0.364817 0.790536 -0.475643 -0.385766 0.790536 -0.458129 -0.40641 0.790536 -0.439338 -0.426655 0.790536 -0.419262 -0.446399 0.790536 -0.397902 -0.465538 0.790536 -0.375271 -0.483966 0.790536 -0.351392 -0.501573 0.790536 -0.355577 -0.564749 0.744731 -0.272667 -0.548366 0.790536 -0.244257 -0.561596 0.790536 -0.214893 -0.573475 0.790536 -0.184667 -0.583909 0.790536 -0.153687 -0.592817 0.790536 -0.122068 -0.600126 0.790536 -0.0801054 -0.539575 0.838118 -0.0511412 -0.543086 0.838118 -0.0625675 -0.664426 0.744731 0.0082199 -0.61236 0.790536 0.0410553 -0.611037 0.790536 0.0737141 -0.607962 0.790536 0.106057 -0.603162 0.790536 0.13795 -0.596676 0.790536 0.169265 -0.588559 0.790536 0.217816 -0.630819 0.744731 0.258587 -0.555144 0.790536 0.3961 -0.537104 0.744731 0.421446 -0.517455 0.744731 0.489172 -0.453968 0.744731 0.508952 -0.431676 0.744731 0.429461 -0.436596 0.790536 0.408742 -0.456051 0.790536 0.469558 -0.27762 0.838118 0.398904 -0.235847 0.886144 0.480295 -0.258601 0.838118 0.587605 -0.316379 0.744731 0.599525 -0.293165 0.744731 0.610277 -0.270071 0.744731 0.619911 -0.247157 0.744731 0.527169 -0.311681 0.790536 0.642632 -0.18 0.744731 0.648324 -0.158278 0.744731 0.583665 -0.185439 0.790536 0.576731 -0.205994 0.790536 0.653163 -0.136944 0.744731 0.660492 -0.0955295 0.744731 0.608485 -0.0692708 0.790536 0.610262 -0.0513011 0.790536 0.66635 -0.0367922 0.744731 0.667118 -0.0181563 0.744731 -0.0568968 -0.0015485 0.998379 -0.0625833 -1.35328e-16 0.99804 -0.180593 -1.156e-16 0.983558 0.611484 0.0337627 0.790536 0.241412 0.00657025 0.9704 0.190693 -2.26904e-17 0.98165 0.0991181 0.00269759 0.995072 0.603089 0.106468 0.790536 0.456353 0.0805631 0.886144 0.533881 0.111935 0.838118 0.537182 0.0948325 0.838118 0.441654 0.14032 0.886144 0.51988 0.165174 0.838118 0.446235 0.124989 0.886144 0.513704 0.183482 0.838118 0.436408 0.155874 0.886144 0.550161 0.269026 0.790536 0.416302 0.20357 0.886144 0.480295 0.258601 0.838118 0.490038 0.239626 0.838118 0.457792 0.296622 0.838118 0.388908 0.25199 0.886144 0.444962 0.315542 0.838118 0.483926 0.375324 0.790536 0.431041 0.334308 0.838118 0.416005 0.352842 0.838118 0.276762 0.23474 0.931826 0.34448 0.422956 0.838118 0.323763 0.439016 0.838118 0.338995 0.510034 0.790536 0.255179 0.482122 0.838118 0.230328 0.494476 0.838118 0.204588 0.50567 0.838118 0.178038 0.515617 0.838118 0.150767 0.52424 0.838118 0.0802525 0.456408 0.886144 0.104386 0.4515 0.886144 0.106057 0.603162 0.790536 0.0365688 0.544262 0.838118 0.00732169 0.54544 0.838118 -0.0219572 0.545047 0.838118 -0.0511411 0.543086 0.838118 -0.0801054 0.539575 0.838118 -0.108728 0.534543 0.838118 -0.139736 0.441839 0.886144 -0.116294 0.44858 0.886144 -0.184667 0.583909 0.790536 -0.217564 0.500224 0.838118 -0.242869 0.488439 0.838118 -0.246908 0.392154 0.886144 -0.29064 0.461613 0.838118 -0.227036 0.403984 0.886144 -0.312991 0.44676 0.838118 -0.334261 0.431077 0.838118 -0.354418 0.414663 0.838118 -0.373444 0.397615 0.838118 -0.391326 0.380029 0.838118 -0.408064 0.361997 0.838118 -0.475643 0.385766 0.790536 -0.451512 0.306097 0.838118 -0.463806 0.287127 0.838118 -0.533338 0.301003 0.790536 -0.485288 0.249104 0.838118 -0.494549 0.230172 0.838118 -0.564573 0.237296 0.790536 -0.572919 0.21637 0.790536 -0.527689 0.138212 0.838118 -0.444026 0.132625 0.886144 -0.448288 0.117416 0.886144 -0.592431 0.15517 0.790536 -0.597257 0.135411 0.790536 -0.601325 0.116019 0.790536 -0.604682 0.097015 0.790536 -0.607374 0.0784151 0.790536 -0.609446 0.0602326 0.790536 -0.61094 0.0424777 0.790536 -0.611898 0.0251571 0.790536 -0.612359 0.00827553 0.790536 -0.612359 -0.00827542 0.790536 -0.611898 -0.0251572 0.790536 -0.61094 -0.0424777 0.790536 -0.609446 -0.0602326 0.790536 -0.607374 -0.078415 0.790536 -0.604682 -0.097015 0.790536 -0.597257 -0.135411 0.790536 -0.592431 -0.15517 0.790536 -0.586799 -0.17527 0.790536 -0.494549 -0.230172 0.838118 -0.427208 -0.17956 0.886144 -0.420135 -0.195538 0.886144 -0.555225 -0.258412 0.790536 -0.544829 -0.279667 0.790536 -0.520711 -0.322355 0.790536 -0.359916 -0.291906 0.886144 -0.423664 -0.343609 0.838118 -0.372213 -0.276054 0.886144 -0.408064 -0.361997 0.838118 -0.317252 -0.337786 0.886144 -0.373444 -0.397615 0.838118 -0.332444 -0.322846 0.886144 -0.354418 -0.414663 0.838118 -0.334261 -0.431077 0.838118 -0.246908 -0.392154 0.886144 -0.29064 -0.461613 0.838118 -0.265896 -0.379536 0.886144 -0.267248 -0.475538 0.838118 -0.242869 -0.488439 0.838118 -0.217564 -0.500224 0.838118 -0.191409 -0.510804 0.838118 -0.164487 -0.520098 0.838118 -0.0923677 -0.454111 0.886144 -0.108728 -0.534543 0.838118 -0.116294 -0.44858 0.886144 -0.068052 -0.458386 0.886144 -0.0899336 -0.605776 0.790536 -0.0219571 -0.545047 0.838118 0.0073216 -0.54544 0.838118 0.0365686 -0.544262 0.838118 0.0656584 -0.541523 0.838118 0.0944669 -0.537247 0.838118 0.122874 -0.531469 0.838118 0.151248 -0.438032 0.886144 0.178038 -0.515617 0.838118 0.128081 -0.445358 0.886144 0.204588 -0.50567 0.838118 0.230328 -0.494476 0.838118 0.255179 -0.482122 0.838118 0.0588513 -0.0798011 0.995072 0.062617 -0.0768816 0.995072 0.363486 -0.492879 0.790536 0.386745 -0.474848 0.790536 0.448894 -0.416588 0.790536 0.467045 -0.396132 0.790536 0.324969 -0.330368 0.886144 0.382528 -0.388883 0.838118 0.309292 -0.34509 0.886144 0.499555 -0.354256 0.790536 0.364074 -0.406212 0.838118 0.513958 -0.333015 0.790536 0.539223 -0.290329 0.790536 0.550161 -0.269026 0.790536 0.560027 -0.247833 0.790536 0.568868 -0.226806 0.790536 0.589719 -0.165179 0.790536 0.594942 -0.145246 0.790536 0.51988 -0.165174 0.838118 0.513704 -0.183482 0.838118 0.603089 -0.106468 0.790536 0.606108 -0.0876637 0.790536 0.537182 -0.0948325 0.838118 0.599383 -0.125668 0.790536 0.541988 -0.0617007 0.838118 0.543571 -0.0456948 0.838118 0.612188 -0.0166613 0.790536 0.611484 -0.0337627 0.790536 0.544659 0.030073 0.838118 0.543571 0.0456948 0.838118 0.0988063 0.00830606 0.995072 0.0985185 0.0112155 0.995072 0.239952 0.0273165 0.9704 0.450188 0.109906 0.886144 0.453548 0.0950919 0.886144 0.355182 0.0744683 0.931826 0.525273 0.147128 0.838118 0.430458 0.171623 0.886144 0.341759 0.122068 0.931826 0.3371 0.134401 0.931826 0.398904 0.235847 0.886144 0.408026 0.21969 0.886144 0.319533 0.172043 0.931826 0.378009 0.268063 0.886144 0.296026 0.209925 0.931826 0.366183 0.284005 0.886144 0.309292 0.34509 0.886144 0.292646 0.359314 0.886144 0.200881 0.302236 0.931826 0.256515 0.385939 0.886144 0.215395 0.29207 0.931826 0.23708 0.398173 0.886144 0.216782 0.409578 0.886144 0.195671 0.420073 0.886144 0.173804 0.429582 0.886144 0.151249 0.438032 0.886144 0.0817464 0.353578 0.931826 0.100303 0.348768 0.931826 0.122874 0.531469 0.838118 0.0557789 0.46004 0.886144 0.0310664 0.462367 0.886144 0.00622 0.463368 0.886144 -0.0186533 0.463034 0.886144 -0.043446 0.461368 0.886144 -0.068052 0.458386 0.886144 -0.0923678 0.454111 0.886144 -0.136892 0.528033 0.838118 -0.162608 0.433944 0.886144 -0.184828 0.424955 0.886144 -0.206325 0.414944 0.886144 -0.267249 0.475538 0.838118 -0.265896 0.379536 0.886144 -0.235789 0.275869 0.931826 -0.301089 0.352269 0.886144 -0.222378 0.286789 0.931826 -0.317252 0.337786 0.886144 -0.332444 0.322846 0.886144 -0.346663 0.307527 0.886144 -0.359915 0.291906 0.886144 -0.372213 0.276054 0.886144 -0.383573 0.260038 0.886144 -0.394018 0.243923 0.886144 -0.475053 0.268109 0.838118 -0.412268 0.211622 0.886144 -0.420135 0.195538 0.886144 -0.502875 0.211364 0.838118 -0.510309 0.192725 0.838118 -0.516893 0.174297 0.838118 -0.522672 0.156116 0.838118 -0.531987 0.120613 0.838118 -0.535611 0.10334 0.838118 -0.538601 0.086413 0.838118 -0.540999 0.0698457 0.838118 -0.542844 0.0536502 0.838118 -0.544175 0.0378356 0.838118 -0.545028 0.0224079 0.838118 -0.545439 0.00737116 0.838118 -0.545439 -0.00737106 0.838118 -0.545028 -0.022408 0.838118 -0.544175 -0.0378356 0.838118 -0.542844 -0.0536502 0.838118 -0.540999 -0.0698456 0.838118 -0.457558 -0.0734105 0.886144 -0.455018 -0.0877908 0.886144 -0.531987 -0.120613 0.838118 -0.527689 -0.138212 0.838118 -0.444026 -0.132625 0.886144 -0.439117 -0.148071 0.886144 -0.510309 -0.192725 0.838118 -0.502875 -0.211364 0.838118 -0.412268 -0.211622 0.886144 -0.403573 -0.227767 0.886144 -0.394018 -0.243923 0.886144 -0.383573 -0.260038 0.886144 -0.43814 -0.324949 0.838118 -0.346663 -0.307528 0.886144 -0.391326 -0.380029 0.838118 -0.301089 -0.352269 0.886144 -0.283965 -0.366213 0.886144 -0.312991 -0.44676 0.838118 -0.227036 -0.403984 0.886144 -0.206325 -0.414944 0.886144 -0.184828 -0.424955 0.886144 -0.162608 -0.433944 0.886144 -0.0910719 -0.351292 0.931826 -0.10943 -0.346013 0.931826 -0.136892 -0.528033 0.838118 -0.043446 -0.461368 0.886144 -0.0186532 -0.463034 0.886144 0.00621993 -0.463368 0.886144 0.0310662 -0.462367 0.886144 0.0557788 -0.46004 0.886144 0.0802526 -0.456408 0.886144 0.100303 -0.348768 0.931826 0.0817464 -0.353578 0.931826 0.150767 -0.52424 0.838118 0.173804 -0.429582 0.886144 0.195671 -0.420073 0.886144 0.185662 -0.311817 0.931826 0.169766 -0.320748 0.931826 0.34448 -0.422955 0.838118 0.399838 -0.371063 0.838118 0.444962 -0.315542 0.838118 0.341759 -0.122068 0.931826 0.22743 -0.0812322 0.9704 0.345868 -0.109887 0.931826 0.457792 -0.296622 0.838118 0.490038 -0.239626 0.838118 0.498826 -0.220749 0.838118 0.506701 -0.20202 0.838118 0.525273 -0.147128 0.838118 0.529925 -0.129373 0.838118 0.436408 -0.155874 0.886144 0.441654 -0.14032 0.886144 0.533881 -0.111935 0.838118 0.539871 -0.0780836 0.838118 0.456353 -0.0805632 0.886144 0.460435 -0.0524167 0.886144 0.461781 -0.0388191 0.886144 0.545287 -0.0148405 0.838118 0.544659 -0.0300731 0.838118 0.392677 5.22397e-17 0.919676 0.362771 0.00987314 0.931826 0.462705 0.025548 0.886144 0.461781 0.0388192 0.886144 0.460435 0.0524167 0.886144 0.458637 0.0663343 0.886144 0.0981337 0.0141934 0.995072 0.239014 0.0345695 0.9704 0.349456 0.0978816 0.931826 0.352551 0.0860698 0.931826 0.234611 0.0572767 0.9704 0.230164 0.0731265 0.9704 0.345868 0.109887 0.931826 0.232551 0.065137 0.9704 0.423768 0.187533 0.886144 0.331861 0.146861 0.931826 0.304561 0.197338 0.931826 0.31239 0.184696 0.931826 0.207885 0.122909 0.9704 0.190833 0.148006 0.9704 0.242212 0.270246 0.931826 0.229177 0.281385 0.931826 0.275047 0.372958 0.886144 0.185662 0.311817 0.931826 0.169766 0.320748 0.931826 0.153233 0.328967 0.931826 0.136109 0.336414 0.931826 0.0667483 0.232094 0.9704 0.0788218 0.228276 0.9704 0.128081 0.445358 0.886144 0.0628473 0.357422 0.931826 0.0436815 0.360266 0.931826 0.0243287 0.362088 0.931826 0.004871 0.362872 0.931826 -0.0146078 0.362611 0.931826 -0.0340234 0.361307 0.931826 -0.0532928 0.358971 0.931826 -0.0606055 0.233773 0.9704 -0.091072 0.351292 0.931826 -0.0481366 0.236656 0.9704 -0.10943 0.346013 0.931826 -0.127341 0.33983 0.931826 -0.144742 0.332791 0.931826 -0.118318 0.210532 0.9704 -0.177796 0.316368 0.931826 -0.107524 0.216244 0.9704 -0.193358 0.307103 0.931826 -0.208228 0.297222 0.931826 -0.283965 0.366214 0.886144 -0.248446 0.264527 0.931826 -0.260343 0.252827 0.931826 -0.271478 0.240831 0.931826 -0.281857 0.228597 0.931826 -0.291487 0.216183 0.931826 -0.210318 0.118698 0.9704 -0.316045 0.178368 0.931826 -0.205338 0.127118 0.9704 -0.403573 0.227767 0.886144 -0.334555 0.140617 0.931826 -0.218949 0.101903 0.9704 -0.222635 0.093576 0.9704 -0.427208 0.17956 0.886144 -0.433523 0.163726 0.886144 -0.439117 0.148071 0.886144 -0.347725 0.103861 0.931826 -0.351063 0.0919504 0.931826 -0.45194 0.102464 0.886144 -0.455018 0.0877908 0.886144 -0.457558 0.0734105 0.886144 -0.459595 0.0593361 0.886144 -0.461163 0.0455775 0.886144 -0.462293 0.0321425 0.886144 -0.463018 0.0190362 0.886144 -0.463367 0.00626203 0.886144 -0.463367 -0.00626194 0.886144 -0.463018 -0.0190363 0.886144 -0.462293 -0.0321425 0.886144 -0.461163 -0.0455775 0.886144 -0.459595 -0.059336 0.886144 -0.353923 -0.0802418 0.931826 -0.237128 -0.0457514 0.9704 -0.235524 -0.0533984 0.9704 -0.45194 -0.102464 0.886144 -0.448288 -0.117416 0.886144 -0.347725 -0.103861 0.931826 -0.343881 -0.115957 0.931826 -0.433523 -0.163726 0.886144 -0.334555 -0.140617 0.931826 -0.329015 -0.15313 0.931826 -0.322854 -0.165725 0.931826 -0.316045 -0.178368 0.931826 -0.308563 -0.191021 0.931826 -0.300383 -0.203641 0.931826 -0.281857 -0.228597 0.931826 -0.291487 -0.216183 0.931826 -0.271478 -0.240831 0.931826 -0.248446 -0.264527 0.931826 -0.260343 -0.252827 0.931826 -0.235789 -0.275869 0.931826 -0.138569 -0.197792 0.9704 -0.208228 -0.297222 0.931826 -0.147986 -0.190849 0.9704 -0.193358 -0.307103 0.931826 -0.177796 -0.316368 0.931826 -0.161577 -0.324951 0.931826 -0.144742 -0.332791 0.931826 -0.0728223 -0.23026 0.9704 -0.0847415 -0.226146 0.9704 -0.139736 -0.441839 0.886144 -0.0723349 -0.355623 0.931826 -0.0532928 -0.35897 0.931826 -0.0340234 -0.361307 0.931826 -0.0146077 -0.362611 0.931826 0.00487095 -0.362872 0.931826 0.0243285 -0.362088 0.931826 0.0436815 -0.360266 0.931826 0.0543996 -0.235295 0.9704 0.0418229 -0.237852 0.9704 0.104386 -0.4515 0.886144 0.118446 -0.343031 0.931826 0.136109 -0.336414 0.931826 0.153234 -0.328967 0.931826 0.216782 -0.409578 0.886144 0.292647 -0.359314 0.886144 0.339675 -0.315229 0.886144 -0.0489951 0.0289677 0.998379 0.366183 -0.284004 0.886144 0.378009 -0.268063 0.886144 0.25449 -0.258718 0.931826 0.242212 -0.270246 0.931826 0.388908 -0.25199 0.886144 0.408026 -0.21969 0.886144 0.416302 -0.20357 0.886144 0.423768 -0.187533 0.886144 0.430458 -0.171623 0.886144 0.31239 -0.184696 0.931826 0.446235 -0.12499 0.886144 0.450188 -0.109906 0.886144 0.453548 -0.0950919 0.886144 0.458637 -0.0663344 0.886144 0.357379 -0.0630906 0.931826 0.360576 -0.0410485 0.931826 0.361629 -0.0304 0.931826 0.463238 -0.0126075 0.886144 0.462705 -0.025548 0.886144 0.299582 -9.43661e-17 0.95407 0.362353 0.0200071 0.931826 0.361629 0.0304 0.931826 0.360576 0.0410486 0.931826 0.359168 0.0519477 0.931826 0.357379 0.0630905 0.931826 0.0976449 0.0172379 0.995072 0.236362 0.0495562 0.9704 0.237824 0.0419847 0.9704 0.0933773 0.033352 0.995072 0.22743 0.0812322 0.9704 0.0944999 0.030024 0.995072 0.224329 0.0894395 0.9704 0.0921042 0.0367217 0.995072 0.326014 0.159419 0.931826 0.216952 0.106088 0.9704 0.202676 0.131322 0.9704 0.286765 0.222409 0.931826 0.169355 0.172168 0.9704 0.161184 0.17984 0.9704 0.0588513 0.0798011 0.995072 0.143338 0.194363 0.9704 0.062617 0.0768817 0.995072 0.13368 0.201128 0.9704 0.123552 0.207504 0.9704 0.112974 0.213448 0.9704 0.101972 0.218917 0.9704 0.0323623 0.0937247 0.995072 0.0371884 0.0919168 0.995072 0.118446 0.343031 0.931826 0.0543996 0.235295 0.9704 0.0418228 0.237852 0.9704 0.0290686 0.239746 0.9704 0.0161899 0.240958 0.9704 0.0032415 0.24148 0.9704 -0.009721 0.241306 0.9704 -0.0226414 0.240438 0.9704 -0.0197637 0.097165 0.995072 -0.014561 0.0980799 0.995072 -0.072335 0.355623 0.931826 -0.0728223 0.230261 0.9704 -0.0847414 0.226146 0.9704 -0.0963212 0.221461 0.9704 -0.161577 0.324951 0.931826 -0.128674 0.204367 0.9704 -0.138569 0.197792 0.9704 -0.15691 0.183582 0.9704 -0.147986 0.190849 0.9704 -0.0711323 0.0690787 0.995072 -0.17325 0.168248 0.9704 -0.0678818 0.0722755 0.995072 -0.18066 0.160265 0.9704 -0.187567 0.152124 0.9704 -0.193975 0.143863 0.9704 -0.300383 0.203641 0.931826 -0.308563 0.191021 0.931826 -0.322855 0.165725 0.931826 -0.329015 0.15313 0.931826 -0.3395 0.128217 0.931826 -0.343881 0.115957 0.931826 -0.0973593 0.0187844 0.995072 0.0555089 -0.0125851 0.998379 0.0558872 -0.0107828 0.998379 -0.353923 0.0802419 0.931826 -0.356333 0.0687507 0.931826 -0.358322 0.0574891 0.931826 -0.359918 0.0464672 0.931826 -0.361145 0.0356926 0.931826 -0.362031 0.0251714 0.931826 -0.362599 0.0149076 0.931826 -0.362872 0.00490391 0.931826 -0.362872 -0.00490385 0.931826 -0.362599 -0.0149077 0.931826 -0.362031 -0.0251714 0.931826 -0.361145 -0.0356926 0.931826 -0.359918 -0.0464671 0.931826 -0.358322 -0.0574892 0.931826 -0.356333 -0.0687507 0.931826 -0.351063 -0.0919504 0.931826 -0.0927601 -0.0350321 0.995072 -0.225926 -0.0853241 0.9704 -0.0939569 -0.0316824 0.995072 -0.3395 -0.128217 0.931826 -0.222635 -0.0935759 0.9704 -0.218949 -0.101903 0.9704 -0.214849 -0.110285 0.9704 -0.210318 -0.118698 0.9704 -0.205339 -0.127118 0.9704 -0.199896 -0.135517 0.9704 -0.187567 -0.152124 0.9704 -0.193975 -0.143863 0.9704 -0.0711323 -0.0690787 0.995072 -0.17325 -0.168248 0.9704 -0.0741748 -0.0658011 0.995072 -0.165333 -0.176034 0.9704 -0.15691 -0.183582 0.9704 -0.222378 -0.286789 0.931826 -0.128674 -0.204368 0.9704 -0.118318 -0.210533 0.9704 -0.107524 -0.216244 0.9704 -0.0347929 -0.0928501 0.995072 -0.0395472 -0.0909269 0.995072 -0.127341 -0.33983 0.931826 -0.0606054 -0.233773 0.9704 -0.0481366 -0.236655 0.9704 -0.0354647 -0.238883 0.9704 -0.0226415 -0.240438 0.9704 -0.00972094 -0.241306 0.9704 0.00324146 -0.24148 0.9704 0.0161899 -0.240958 0.9704 0.0171715 -0.0976566 0.995072 0.0119349 -0.0984339 0.995072 0.0628473 -0.357422 0.931826 0.0667483 -0.232094 0.9704 0.0788217 -0.228276 0.9704 0.0905762 -0.223872 0.9704 0.101972 -0.218917 0.9704 0.123552 -0.207504 0.9704 0.112974 -0.213448 0.9704 0.13368 -0.201128 0.9704 0.266006 -0.246862 0.931826 0.276762 -0.23474 0.931826 0.286765 -0.222409 0.931826 0.296026 -0.209925 0.931826 0.169355 -0.172168 0.9704 0.161184 -0.17984 0.9704 0.304561 -0.197338 0.931826 0.319533 -0.172043 0.931826 0.326014 -0.159419 0.931826 0.331861 -0.146861 0.931826 0.3371 -0.134401 0.931826 0.207885 -0.122909 0.9704 0.349456 -0.0978817 0.931826 0.352551 -0.0860698 0.931826 0.230164 -0.0731265 0.9704 0.355182 -0.0744683 0.931826 0.359168 -0.0519477 0.931826 0.239952 -0.0273165 0.9704 0.240653 -0.0202302 0.9704 0.362353 -0.0200071 0.931826 0.36277 -0.00987317 0.931826 -0.521825 -6.66013e-17 0.853053 -0.525217 -0.0142943 0.850848 -0.452963 -1.43047e-16 0.891529 0.241134 0.0133141 0.9704 0.240653 0.0202302 0.9704 0.0963258 0.0235165 0.995072 0.0970448 0.0203466 0.995072 -0.0557064 -0.0116795 0.998379 0.0954801 0.0267437 0.995072 -0.0552939 -0.0134992 0.998379 0.220843 0.0977313 0.9704 0.0906729 0.0401262 0.995072 -0.0528706 -0.0210794 0.998379 -0.0520488 -0.0230336 0.998379 0.212639 0.114489 0.9704 0.0873044 0.0470065 0.995072 0.0853528 0.0504636 0.995072 -0.0489949 -0.0289675 0.998379 0.0832139 0.0539177 0.995072 0.196996 0.139698 0.9704 0.0808819 0.0573568 0.995072 0.0695331 0.0706883 0.995072 0.0661785 0.0738382 0.995072 0.15251 0.187253 0.9704 0.0548859 0.0825785 0.995072 0.0507275 0.0851963 0.995072 0.0463844 0.0876365 0.995072 -0.0213473 -0.052763 0.998379 -0.0240331 -0.0515951 0.998379 0.0905762 0.223873 0.9704 0.0274053 0.0952923 0.995072 0.0223352 0.0966065 0.995072 0.0171715 0.0976566 0.995072 0.0119349 0.0984339 0.995072 0.00664721 0.0989318 0.995072 0.00133088 0.0991459 0.995072 -0.00399121 0.0990745 0.995072 0.00835843 -0.0563008 0.998379 0.00533621 -0.0566672 0.998379 -0.0354647 0.238883 0.9704 -0.0248832 0.0959818 0.995072 -0.0298991 0.0945395 0.995072 -0.0347928 0.0928501 0.995072 -0.0395472 0.0909269 0.995072 -0.0485784 0.0864397 0.995072 -0.0441469 0.0887848 0.995072 -0.0528304 0.0839085 0.995072 0.0348777 -0.0449799 0.998379 -0.0607594 0.078358 0.995072 0.0326584 -0.0466162 0.998379 -0.0644234 0.0753742 0.995072 -0.165333 0.176034 0.9704 0.0442061 -0.035853 0.998379 -0.0770104 0.0624586 0.995072 0.0425784 -0.0377717 0.998379 0.0471119 -0.0319389 0.998379 -0.0820724 0.0556399 0.995072 0.0457166 -0.033906 0.998379 -0.199895 0.135517 0.9704 -0.0863516 0.0487348 0.995072 -0.0843072 0.0521918 0.995072 -0.214849 0.110285 0.9704 -0.0898952 0.0418389 0.995072 -0.0914088 0.0384201 0.995072 -0.225927 0.0853242 0.9704 -0.228842 0.0771656 0.9704 -0.2314 0.0691163 0.9704 -0.233621 0.06119 0.9704 -0.235524 0.0533984 0.9704 -0.237128 0.0457514 0.9704 -0.238452 0.0382572 0.9704 -0.239514 0.0309224 0.9704 -0.240331 0.0237523 0.9704 -0.24092 0.0167508 0.9704 -0.241298 0.00992053 0.9704 -0.241479 0.0032634 0.9704 -0.241479 -0.00326335 0.9704 -0.241298 -0.00992058 0.9704 -0.24092 -0.0167508 0.9704 -0.240331 -0.0237523 0.9704 -0.239514 -0.0309224 0.9704 -0.238452 -0.0382572 0.9704 -0.0973593 -0.0187844 0.995072 -0.0967006 -0.0219241 0.995072 -0.233621 -0.06119 0.9704 -0.2314 -0.0691163 0.9704 -0.228841 -0.0771657 0.9704 -0.0914088 -0.0384201 0.995072 -0.0898954 -0.041839 0.995072 0.0483949 0.0299597 0.998379 -0.0843072 -0.0521918 0.995072 0.0495685 0.0279752 0.998379 -0.0820724 -0.0556399 0.995072 -0.0770104 -0.0624586 0.995072 -0.0796417 -0.0590667 0.995072 -0.18066 -0.160265 0.9704 -0.0678818 -0.0722755 0.995072 0.0348778 0.0449799 0.998379 -0.0607594 -0.078358 0.995072 0.0369809 0.043267 0.998379 -0.0568932 -0.0812086 0.995072 -0.0528304 -0.0839085 0.995072 -0.0485784 -0.0864397 0.995072 0.0227012 0.0521946 0.998379 0.0253416 0.0509651 0.998379 -0.0963212 -0.221462 0.9704 -0.0298991 -0.0945395 0.995072 -0.0248832 -0.0959818 0.995072 -0.0197637 -0.0971652 0.995072 -0.014561 -0.0980799 0.995072 -0.00929606 -0.0987181 0.995072 -0.00399119 -0.0990745 0.995072 0.00133086 -0.0991457 0.995072 -0.00685096 0.0565038 0.998379 -0.00381568 0.0567898 0.998379 0.0290686 -0.239746 0.9704 0.0223352 -0.0966065 0.995072 0.0274053 -0.0952923 0.995072 0.0323623 -0.0937249 0.995072 -0.0266261 0.050306 0.998379 0.0463844 -0.0876365 0.995072 0.0507274 -0.0851961 0.995072 0.0548859 -0.0825786 0.995072 0.177018 -0.164279 0.9704 0.184176 -0.156212 0.9704 0.190833 -0.148006 0.9704 0.196996 -0.139698 0.9704 0.0695331 -0.0706883 0.995072 0.0661785 -0.0738382 0.995072 0.202676 -0.131322 0.9704 0.212639 -0.114489 0.9704 0.216952 -0.106088 0.9704 0.220843 -0.0977313 0.9704 0.224329 -0.0894395 0.9704 0.0853528 -0.0504636 0.995072 -0.0542458 0.0172347 0.998379 0.0944999 -0.030024 0.995072 -0.0536012 0.019145 0.998379 0.232551 -0.0651371 0.9704 0.234611 -0.0572767 0.9704 0.0933773 -0.033352 0.995072 0.237824 -0.0419848 0.9704 0.236362 -0.0495563 0.9704 0.239015 -0.0345696 0.9704 0.0976449 -0.0172379 0.995072 0.0985185 -0.0112155 0.995072 0.0988063 -0.00830606 0.995072 0.241412 -0.00657028 0.9704 0.241134 -0.0133141 0.9704 0.0673443 -2.16811e-16 0.99773 0.099004 0.00546645 0.995072 -0.432487 -0.0117705 0.901563 -0.324982 -0.00884468 0.945679 -0.374419 2.49651e-17 0.92726 -0.198976 -0.0226518 0.979743 -0.32396 -0.0272334 0.945679 -0.323016 -0.0367727 0.945679 -0.321754 -0.0465364 0.945679 -0.198199 -0.0286662 0.979743 -0.19284 -0.0540139 0.979743 -0.19086 -0.060639 0.979743 -0.0542458 -0.0172347 0.998379 -0.188593 -0.0673605 0.979743 -0.0536014 -0.0191451 0.998379 0.0890754 0.0435574 0.995072 -0.0501152 -0.0269831 0.998379 -0.0511318 -0.0250032 0.998379 -0.179904 -0.0879721 0.979743 -0.0477671 -0.0309503 0.998379 -0.168066 -0.108897 0.979743 -0.0399141 -0.0405772 0.998379 -0.0379883 -0.0423852 0.998379 -0.13366 -0.14913 0.979743 -0.0359439 -0.0441322 0.998379 -0.0337823 -0.045808 0.998379 -0.0315061 -0.0474024 0.998379 -0.029119 -0.048905 0.998379 -0.0266261 -0.050306 0.998379 -0.0936819 -0.176998 0.979743 0.0418673 0.0898822 0.995072 -0.018577 -0.0538009 0.998379 -0.0157315 -0.0547007 0.998379 -0.012821 -0.0554549 0.998379 -0.0098569 -0.0560577 0.998379 -0.00685097 -0.0565038 0.998379 -0.00381569 -0.0567896 0.998379 -0.000763964 -0.0569125 0.998379 -0.00268796 -0.200243 0.979743 0.00229108 -0.0568717 0.998379 0.00806099 -0.200099 0.979743 -0.00929605 0.0987181 0.995072 0.011345 -0.0557758 0.998379 0.0142837 -0.0550965 0.998379 0.0171629 -0.0542683 0.998379 0.0199721 -0.0532986 0.998379 0.0227012 -0.0521946 0.998379 0.0798728 -0.183644 0.979743 0.0253415 -0.0509649 0.998379 0.0278854 -0.0496188 0.998379 0.0303262 -0.048166 0.998379 -0.0568932 0.0812087 0.995072 0.0369811 -0.0432671 0.998379 0.0408319 -0.0396531 0.998379 0.0389662 -0.0414883 0.998379 -0.0741748 0.0658011 0.995072 -0.0796417 0.0590667 0.995072 0.0495685 -0.0279752 0.998379 0.0483949 -0.0299597 0.998379 -0.0882121 0.0452803 0.995072 0.0516027 -0.0240168 0.998379 0.0524714 -0.0220543 0.998379 -0.0927601 0.0350321 0.995072 -0.0939569 0.0316824 0.995072 -0.0950073 0.0283775 0.995072 -0.0959193 0.0251232 0.995072 -0.0967006 0.0219241 0.995072 -0.0979028 0.0157075 0.995072 -0.0983386 0.012696 0.995072 -0.0986741 0.00975213 0.995072 -0.098916 0.00687747 0.995072 -0.0990711 0.00407313 0.995072 -0.0991458 0.00133987 0.995072 -0.0991458 -0.00133986 0.995072 -0.0990711 -0.00407316 0.995072 -0.098916 -0.00687747 0.995072 -0.0986741 -0.00975213 0.995072 -0.0983387 -0.012696 0.995072 -0.0979028 -0.0157075 0.995072 0.0555091 0.0125851 0.998379 0.195305 0.0442798 0.979743 0.0550603 0.0144214 0.998379 -0.0959193 -0.0251232 0.995072 -0.0950073 -0.0283775 0.995072 0.0532469 0.0201094 0.998379 0.0539339 0.0181866 0.998379 0.0516027 0.0240168 0.998379 0.18156 0.0845015 0.979743 0.0506364 0.0259923 0.998379 -0.0882121 -0.0452804 0.995072 -0.0863516 -0.0487348 0.995072 0.047112 0.031939 0.998379 0.16576 0.112375 0.979743 0.0457168 0.0339061 0.998379 0.0442061 0.035853 0.998379 0.0408319 0.0396531 0.998379 0.0425784 0.0377717 0.998379 0.0389661 0.0414881 0.998379 -0.0644235 -0.0753743 0.995072 0.0326584 0.0466162 0.998379 0.0303262 0.048166 0.998379 0.0278855 0.049619 0.998379 -0.0441469 -0.0887848 0.995072 0.0199721 0.0532986 0.998379 0.0171629 0.0542683 0.998379 0.0142836 0.0550963 0.998379 0.0113449 0.0557755 0.998379 0.00835843 0.0563008 0.998379 0.00533622 0.0566672 0.998379 0.00229106 0.0568717 0.998379 -0.000763958 0.0569128 0.998379 -0.00268793 0.200243 0.979743 0.00664717 -0.0989318 0.995072 -0.00985692 0.0560577 0.998379 -0.012821 0.0554549 0.998379 -0.0157314 0.0547005 0.998379 -0.0185769 0.0538007 0.998379 -0.0291191 0.0489052 0.998379 -0.0315062 0.0474026 0.998379 -0.110852 0.166783 0.979743 -0.0337823 0.045808 0.998379 0.0726795 -0.067449 0.995072 0.0756184 -0.0641369 0.995072 0.0783514 -0.0607679 0.995072 0.0808819 -0.0573568 0.995072 0.0832139 -0.0539177 0.995072 0.0873044 -0.0470066 0.995072 0.0890754 -0.0435574 0.995072 0.0906729 -0.0401262 0.995072 0.0921042 -0.0367217 0.995072 0.0954801 -0.0267438 0.995072 0.0963258 -0.0235165 0.995072 0.0970446 -0.0203466 0.995072 0.0981337 -0.0141934 0.995072 -0.0560512 0.0098951 0.998379 -0.0565524 0.00643801 0.998379 -0.0567176 0.00476791 0.998379 0.0991181 -0.0026976 0.995072 0.099004 -0.00546645 0.995072 -0.200187 -0.00544828 0.979743 -0.0568311 -0.0031379 0.998379 -0.0567176 -0.00476791 0.998379 -0.0565524 -0.00643802 0.998379 -0.0563315 -0.00814742 0.998379 -0.0560509 -0.00989506 0.998379 -0.320152 -0.0565186 0.945679 -0.196 -0.0410937 0.979743 -0.197212 -0.0348152 0.979743 -0.194548 -0.0474958 0.979743 -0.318184 -0.0667112 0.945679 -0.0548085 -0.0153517 0.998379 -0.186021 -0.0741663 0.979743 -0.306159 -0.109352 0.945679 -0.301985 -0.120401 0.945679 -0.172386 -0.101921 0.979743 -0.176327 -0.0949383 0.979743 -0.286248 -0.154122 0.945679 -0.14679 -0.136226 0.979743 -0.126466 -0.155276 0.979743 -0.118861 -0.161173 0.979743 -0.102453 -0.172069 0.979743 -0.166322 -0.279336 0.945679 -0.0845586 -0.181534 0.979743 -0.0751089 -0.185643 0.979743 -0.0653617 -0.189295 0.979743 -0.05535 -0.19246 0.979743 -0.04511 -0.195115 0.979743 -0.0346809 -0.197235 0.979743 -0.0134253 -0.199811 0.979743 -0.0217944 -0.324371 0.945679 0.0187751 -0.199379 0.979743 0.0294085 -0.19809 0.979743 0.0399165 -0.196243 0.979743 0.0502562 -0.193853 0.979743 0.0702704 -0.187528 0.979743 0.114076 -0.304431 0.945679 0.0891627 -0.179317 0.979743 0.098113 -0.174581 0.979743 0.114906 -0.164016 0.979743 0.122715 -0.158258 0.979743 0.1371 -0.145974 0.979743 0.149809 -0.132897 0.979743 0.160851 -0.119296 0.979743 0.17816 -0.0914519 0.979743 0.174403 -0.0984288 0.979743 0.283124 -0.159788 0.945679 0.0506364 -0.0259923 0.998379 0.184617 -0.0775964 0.979743 0.299705 -0.125969 0.945679 0.187346 -0.0707537 0.979743 0.0532469 -0.0201094 0.998379 0.0539339 -0.0181866 0.998379 0.0545369 -0.0162895 0.998379 0.0550603 -0.0144214 0.998379 0.0561992 -0.00901658 0.998379 0.196635 -0.0379386 0.979743 0.0564494 -0.0072879 0.998379 0.0566419 -0.00559802 0.998379 0.0567808 -0.00394788 0.998379 0.0568696 -0.00233809 0.998379 0.0569125 -0.000769125 0.998379 0.0569125 0.000769115 0.998379 0.0568696 0.00233811 0.998379 0.0567806 0.00394786 0.998379 0.0566417 0.005598 0.998379 0.0564494 0.00728789 0.998379 0.0561992 0.00901658 0.998379 0.0558872 0.0107828 0.998379 0.0545369 0.0162895 0.998379 0.189763 0.0639884 0.979743 0.0524712 0.0220542 0.998379 0.174403 0.0984288 0.979743 0.149809 0.132897 0.979743 0.155537 0.126147 0.979743 0.252497 0.204785 0.945679 0.130115 0.152232 0.979743 0.1371 0.145974 0.979743 0.222566 0.236972 0.945679 0.122715 0.158258 0.979743 0.114906 0.164016 0.979743 0.0891627 0.179317 0.979743 0.098113 0.174581 0.979743 0.159276 0.283413 0.945679 0.0798728 0.183644 0.979743 0.0702705 0.187528 0.979743 0.0603868 0.19094 0.979743 0.0502561 0.193853 0.979743 0.0399165 0.196243 0.979743 0.00806094 0.200099 0.979743 0.0187751 0.199379 0.979743 0.0304793 0.32367 0.945679 0.013086 0.324839 0.945679 -0.0134252 0.199811 0.979743 -0.0241047 0.198805 0.979743 -0.0346809 0.197235 0.979743 -0.04511 0.195115 0.979743 -0.05535 0.19246 0.979743 -0.0936819 0.176998 0.979743 -0.118861 0.161173 0.979743 -0.0417201 0.0387176 0.998379 -0.0434072 0.0368165 0.998379 -0.0449761 0.0348826 0.998379 -0.0464286 0.0329246 0.998379 -0.0477673 0.0309504 0.998379 -0.0511318 0.0250032 0.998379 -0.0520488 0.0230336 0.998379 -0.0528704 0.0210793 0.998379 -0.0552939 0.0134992 0.998379 -0.0548085 0.0153517 0.998379 -0.19284 0.0540139 0.979743 -0.19086 0.060639 0.979743 -0.188593 0.0673606 0.979743 -0.0557067 0.0116796 0.998379 -0.0563315 0.00814743 0.998379 -0.197212 0.0348152 0.979743 -0.0568311 0.0031379 0.998379 -0.0568966 0.0015485 0.998379 -0.284229 -1.77307e-16 0.958757 -0.199957 -0.0110405 0.979743 -0.199557 -0.0167756 0.979743 -0.315827 -0.0771042 0.945679 -0.412336 -0.131005 0.901563 -0.30984 -0.0984407 0.945679 -0.416613 -0.116692 0.901563 -0.183131 -0.0810422 0.979743 -0.297292 -0.131563 0.945679 -0.401883 -0.16023 0.901563 -0.395637 -0.175085 0.901563 -0.272836 -0.176782 0.945679 -0.279849 -0.165457 0.945679 -0.372424 -0.22019 0.901563 -0.247932 -0.210288 0.945679 -0.238297 -0.221147 0.945679 -0.140435 -0.142768 0.979743 -0.216982 -0.242096 0.945679 -0.205304 -0.252074 0.945679 -0.192958 -0.261646 0.945679 -0.110852 -0.166783 0.979743 -0.152082 -0.287337 0.945679 -0.137272 -0.2947 0.945679 -0.121931 -0.301371 0.945679 -0.106108 -0.307299 0.945679 -0.0898546 -0.312438 0.945679 -0.0391314 -0.322739 0.945679 -0.0563007 -0.32019 0.945679 -0.0749251 -0.42611 0.901563 -0.0520761 -0.429502 0.901563 -0.0241047 -0.198805 0.979743 -0.00436361 -0.325073 0.945679 0.0130861 -0.324839 0.945679 0.0304793 -0.32367 0.945679 0.0477415 -0.321578 0.945679 0.0648001 -0.318579 0.945679 0.0815853 -0.314699 0.945679 0.0603868 -0.19094 0.979743 0.129665 -0.298125 0.945679 0.144746 -0.291102 0.945679 0.186538 -0.266262 0.945679 0.173217 -0.275114 0.945679 0.230517 -0.366122 0.901563 0.106701 -0.169469 0.979743 0.222566 -0.236972 0.945679 0.211228 -0.247132 0.945679 0.281102 -0.328884 0.901563 0.130115 -0.152232 0.979743 0.143665 -0.139517 0.979743 0.243199 -0.215744 0.945679 0.155537 -0.126147 0.979743 0.261124 -0.193664 0.945679 0.16576 -0.112375 0.979743 0.170274 -0.105411 0.979743 0.18156 -0.0845015 0.979743 0.189763 -0.0639883 0.979743 0.191885 -0.0573136 0.979743 0.193727 -0.0507409 0.979743 0.195305 -0.0442798 0.979743 0.19929 -0.0196962 0.979743 0.198613 -0.0256419 0.979743 0.322426 -0.0416269 0.945679 0.197733 -0.0317242 0.979743 0.200092 -0.00822644 0.979743 0.200243 -0.00270612 0.979743 0.601155 0.0776121 0.795355 0.671723 0.0867228 0.735709 0.59849 0.0960217 0.795355 0.200243 0.00270608 0.979743 0.200092 0.00822648 0.979743 0.199779 0.0138903 0.979743 0.199779 -0.0138903 0.979743 0.19929 0.0196962 0.979743 0.198613 0.0256419 0.979743 0.197733 0.0317242 0.979743 0.196635 0.0379386 0.979743 0.317056 0.0718833 0.945679 0.193727 0.0507409 0.979743 0.191885 0.0573137 0.979743 0.299705 0.125969 0.945679 0.304136 0.114861 0.945679 0.404745 0.152857 0.901563 0.187346 0.0707537 0.979743 0.184617 0.0775964 0.979743 0.294743 0.137179 0.945679 0.17816 0.091452 0.979743 0.283124 0.159788 0.945679 0.170274 0.105411 0.979743 0.269093 0.182428 0.945679 0.160851 0.119296 0.979743 0.243199 0.215744 0.945679 0.143665 0.139517 0.979743 0.211227 0.247132 0.945679 0.199214 0.256915 0.945679 0.173217 0.275113 0.945679 0.230517 0.366122 0.901563 0.106701 0.169469 0.979743 0.144746 0.291102 0.945679 0.129665 0.298125 0.945679 0.114076 0.304431 0.945679 0.0980313 0.30997 0.945679 0.0815853 0.314699 0.945679 0.0477415 0.321578 0.945679 0.0635345 0.427956 0.901563 0.0294085 0.19809 0.979743 -0.00436355 0.325073 0.945679 -0.0217943 0.324371 0.945679 -0.0391313 0.322739 0.945679 -0.0563007 0.32019 0.945679 -0.0732311 0.316747 0.945679 -0.121931 0.301371 0.945679 -0.106107 0.307299 0.945679 -0.141208 0.408954 0.901563 -0.0653617 0.189295 0.979743 -0.137272 0.2947 0.945679 -0.152082 0.287337 0.945679 -0.102453 0.172069 0.979743 -0.179956 0.270753 0.945679 -0.192958 0.261646 0.945679 -0.385122 0.357405 0.850848 -0.400694 0.339855 0.850848 -0.14679 0.136226 0.979743 -0.152725 0.129536 0.979743 -0.158245 0.122732 0.979743 -0.163356 0.115843 0.979743 -0.168066 0.108897 0.979743 -0.186021 0.0741663 0.979743 -0.297292 0.131563 0.945679 -0.301985 0.120401 0.945679 -0.179904 0.0879721 0.979743 -0.183131 0.0810422 0.979743 -0.279849 0.165457 0.945679 -0.318184 0.0667112 0.945679 -0.320152 0.0565186 0.945679 -0.194548 0.0474958 0.979743 -0.306159 0.109352 0.945679 -0.30984 0.0984407 0.945679 -0.196 0.0410938 0.979743 -0.198199 0.0286663 0.979743 -0.198976 0.0226517 0.979743 -0.199557 0.0167756 0.979743 -0.323016 0.0367726 0.945679 -0.32396 0.0272333 0.945679 -0.200187 0.0054483 0.979743 -0.199957 0.0110405 0.979743 -0.68681 1.55016e-16 0.726837 -0.732042 -1.77628e-16 0.68126 -0.677048 -0.0184265 0.735709 -0.324608 -0.017923 0.945679 -0.60592 -0.0164907 0.795355 -0.637378 -1.67703e-16 0.770551 -0.52204 -0.0594299 0.850848 -0.429871 -0.0489372 0.901563 -0.523565 -0.044013 0.850848 -0.520001 -0.0752096 0.850848 -0.428192 -0.0619308 0.901563 -0.517411 -0.0913421 0.850848 -0.42344 -0.0887794 0.901563 -0.426059 -0.0752151 0.901563 -0.593246 -0.124381 0.795355 -0.510421 -0.124611 0.850848 -0.514231 -0.107815 0.850848 -0.313054 -0.0876856 0.945679 -0.494797 -0.176729 0.850848 -0.407438 -0.145526 0.901563 -0.500746 -0.159094 0.850848 -0.292055 -0.142813 0.945679 -0.388667 -0.190056 0.901563 -0.303397 -0.308438 0.901563 -0.368449 -0.37457 0.850848 -0.28876 -0.322182 0.901563 -0.22798 -0.231768 0.945679 -0.27322 -0.335462 0.901563 -0.239486 -0.360319 0.901563 -0.290835 -0.437576 0.850848 -0.221342 -0.371741 0.901563 -0.179956 -0.270753 0.945679 -0.202391 -0.382389 0.901563 -0.182681 -0.392187 0.901563 -0.162266 -0.401065 0.901563 -0.141208 -0.408954 0.901563 -0.0974562 -0.421528 0.901563 -0.118352 -0.511908 0.850848 -0.0732311 -0.316747 0.945679 -0.0290041 -0.431674 0.901563 -0.0058071 -0.432608 0.901563 0.017415 -0.432296 0.901563 0.0405619 -0.430741 0.901563 0.0635345 -0.427956 0.901563 0.0862361 -0.423965 0.901563 0.13046 -0.412509 0.901563 0.158433 -0.500956 0.850848 0.151813 -0.405137 0.901563 0.0980313 -0.30997 0.945679 0.172558 -0.396746 0.901563 0.192628 -0.387399 0.901563 0.159276 -0.283413 0.945679 0.248245 -0.354342 0.901563 0.199214 -0.256915 0.945679 0.310375 -0.301415 0.901563 0.376923 -0.366042 0.850848 0.323651 -0.287113 0.901563 0.233224 -0.226491 0.945679 0.252497 -0.204785 0.945679 0.35811 -0.242776 0.901563 0.434894 -0.294831 0.850848 0.367861 -0.227731 0.901563 0.269093 -0.182429 0.945679 0.276421 -0.171123 0.945679 0.376782 -0.212647 0.901563 0.289224 -0.148462 0.945679 0.294743 -0.137179 0.945679 0.409967 -0.138241 0.901563 0.404745 -0.152857 0.901563 0.491527 -0.185632 0.850848 0.304136 -0.114861 0.945679 0.30806 -0.103878 0.945679 0.311504 -0.0930424 0.945679 0.314494 -0.0823722 0.945679 0.317056 -0.0718834 0.945679 0.319215 -0.0615891 0.945679 0.320997 -0.0515007 0.945679 0.323526 -0.0319746 0.945679 0.324319 -0.0225494 0.945679 0.324828 -0.0133547 0.945679 0.325073 -0.00439309 0.945679 0.325073 0.00439303 0.945679 0.324828 0.0133548 0.945679 0.324319 0.0225494 0.945679 0.323526 0.0319746 0.945679 0.322426 0.0416268 0.945679 0.320997 0.0515007 0.945679 0.319215 0.0615891 0.945679 0.418529 0.109621 0.901563 0.508267 0.133125 0.850848 0.41455 0.123821 0.901563 0.314494 0.0823722 0.945679 0.311504 0.0930424 0.945679 0.30806 0.103878 0.945679 0.392245 0.182558 0.901563 0.289224 0.148462 0.945679 0.376782 0.212647 0.901563 0.276421 0.171123 0.945679 0.35811 0.242776 0.901563 0.261124 0.193664 0.945679 0.336023 0.272529 0.901563 0.32365 0.287113 0.901563 0.233224 0.226491 0.945679 0.296192 0.315363 0.901563 0.281102 0.328884 0.901563 0.248245 0.354342 0.901563 0.301471 0.430317 0.850848 0.186538 0.266261 0.945679 0.211964 0.377166 0.901563 0.192628 0.387399 0.901563 0.172558 0.396746 0.901563 0.151813 0.405137 0.901563 0.108574 0.418802 0.901563 0.131853 0.508598 0.850848 0.0862361 0.423965 0.901563 0.104726 0.514869 0.850848 0.0648001 0.318579 0.945679 0.040562 0.430741 0.901563 0.0174149 0.432296 0.901563 -0.00580703 0.432608 0.901563 -0.0290039 0.431674 0.901563 -0.0520761 0.429502 0.901563 -0.0749252 0.42611 0.901563 -0.119579 0.415794 0.901563 -0.145218 0.504945 0.850848 -0.0898547 0.312438 0.945679 -0.162266 0.401065 0.901563 -0.182682 0.392187 0.901563 -0.221342 0.371741 0.901563 -0.2688 0.451447 0.850848 -0.239486 0.360319 0.901563 -0.166322 0.279336 0.945679 -0.27322 0.335461 0.901563 -0.331801 0.407388 0.850848 -0.205305 0.252074 0.945679 -0.247932 0.210288 0.945679 -0.256893 0.199242 0.945679 -0.26519 0.188058 0.945679 -0.272836 0.176782 0.945679 -0.286248 0.154122 0.945679 -0.292055 0.142813 0.945679 -0.412336 0.131005 0.901563 -0.313054 0.0876857 0.945679 -0.372424 0.22019 0.901563 -0.315827 0.0771042 0.945679 -0.407438 0.145527 0.901563 -0.321754 0.0465365 0.945679 -0.426059 0.0752152 0.901563 -0.429871 0.0489371 0.901563 -0.431126 0.0362422 0.901563 -0.324608 0.017923 0.945679 -0.324982 0.00884472 0.945679 -0.431989 -0.023852 0.901563 -0.431126 -0.0362422 0.901563 -0.420303 -0.102611 0.901563 -0.50594 -0.141712 0.850848 -0.58885 -0.143759 0.795355 -0.488051 -0.194585 0.850848 -0.570826 -0.203885 0.795355 -0.563043 -0.224484 0.795355 -0.480467 -0.212625 0.850848 -0.554293 -0.245296 0.795355 -0.38094 -0.205106 0.901563 -0.462618 -0.249083 0.850848 -0.452276 -0.267402 0.850848 -0.400694 -0.339855 0.850848 -0.317126 -0.294303 0.901563 -0.350674 -0.391261 0.850848 -0.311847 -0.422858 0.850848 -0.359764 -0.487833 0.795355 -0.256789 -0.3482 0.901563 -0.2688 -0.451447 0.850848 -0.245787 -0.464377 0.850848 -0.221851 -0.476277 0.850848 -0.171485 -0.496639 0.850848 -0.197835 -0.572951 0.795355 -0.145218 -0.504945 0.850848 -0.167532 -0.582533 0.795355 -0.119579 -0.415794 0.901563 -0.0909899 -0.517473 0.850848 -0.0632419 -0.521592 0.850848 -0.0352229 -0.52423 0.850848 -0.00705222 -0.525364 0.850848 0.021149 -0.524986 0.850848 0.0492588 -0.523098 0.850848 0.0771571 -0.519716 0.850848 0.131854 -0.508598 0.850848 0.152114 -0.586747 0.795355 0.108574 -0.418802 0.901563 0.184364 -0.492004 0.850848 0.209557 -0.481813 0.850848 0.257412 -0.458035 0.850848 0.296965 -0.528415 0.795355 0.279943 -0.444623 0.850848 0.211965 -0.377166 0.901563 0.301471 -0.430317 0.850848 0.265114 -0.341903 0.901563 0.341374 -0.399401 0.850848 0.296192 -0.315363 0.901563 0.408071 -0.330962 0.850848 0.470773 -0.381816 0.795355 0.422014 -0.312989 0.850848 0.336023 -0.272529 0.901563 0.347505 -0.257729 0.901563 0.457569 -0.258241 0.850848 0.3849 -0.197574 0.901563 0.392245 -0.182558 0.901563 0.398849 -0.16764 0.901563 0.41455 -0.123821 0.901563 0.418529 -0.109621 0.901563 0.421938 -0.0956626 0.901563 0.424812 -0.081963 0.901563 0.427184 -0.0685373 0.901563 0.429086 -0.0553972 0.901563 0.430549 -0.0425519 0.901563 0.431605 -0.0300088 0.901563 0.432282 -0.0177725 0.901563 0.432608 -0.00584634 0.901563 0.432608 0.00584626 0.901563 0.432282 0.0177726 0.901563 0.431605 0.0300088 0.901563 0.430549 0.0425519 0.901563 0.429086 0.0553971 0.901563 0.427184 0.0685373 0.901563 0.424812 0.081963 0.901563 0.421938 0.0956625 0.901563 0.409967 0.138241 0.901563 0.491527 0.185632 0.850848 0.398849 0.16764 0.901563 0.467427 0.239936 0.850848 0.53925 0.276804 0.795355 0.457569 0.258241 0.850848 0.3849 0.197574 0.901563 0.446735 0.276559 0.850848 0.515379 0.319054 0.795355 0.434894 0.294831 0.850848 0.367861 0.227731 0.901563 0.347505 0.257729 0.901563 0.408071 0.330962 0.850848 0.376923 0.366041 0.850848 0.43484 0.422286 0.795355 0.359699 0.38298 0.850848 0.310375 0.301415 0.901563 0.341374 0.399401 0.850848 0.265114 0.341903 0.901563 0.279943 0.444623 0.850848 0.257412 0.458035 0.850848 0.23393 0.470462 0.850848 0.209557 0.481813 0.850848 0.158433 0.500956 0.850848 0.182777 0.57793 0.795355 0.13046 0.412509 0.901563 0.0771571 0.519716 0.850848 0.0492589 0.523098 0.850848 0.0211489 0.524986 0.850848 -0.00705213 0.525364 0.850848 -0.0352227 0.52423 0.850848 -0.0632418 0.521592 0.850848 -0.118352 0.511908 0.850848 -0.136537 0.590566 0.795355 -0.0974562 0.421528 0.901563 -0.171485 0.496639 0.850848 -0.197058 0.487058 0.850848 -0.221851 0.476277 0.850848 -0.202391 0.382389 0.901563 -0.290835 0.437576 0.850848 -0.256789 0.3482 0.901563 -0.350674 0.391261 0.850848 -0.329949 0.279852 0.901563 -0.341874 0.265151 0.901563 -0.352916 0.250268 0.901563 -0.363091 0.235262 0.901563 -0.38094 0.205106 0.901563 -0.395637 0.175085 0.901563 -0.401883 0.16023 0.901563 -0.452276 0.267402 0.850848 -0.577688 0.18354 0.795355 -0.500746 0.159094 0.850848 -0.570826 0.203885 0.795355 -0.416613 0.116692 0.901563 -0.420303 0.10261 0.901563 -0.494797 0.176729 0.850848 -0.42344 0.0887794 0.901563 -0.428192 0.0619309 0.901563 -0.517411 0.0913422 0.850848 -0.52204 0.0594298 0.850848 -0.523565 0.044013 0.850848 -0.432487 0.0117706 0.901563 -0.431989 0.023852 0.901563 -0.58279 -4.20884e-16 0.812623 -0.524613 -0.0289662 0.850848 -0.797813 -0.0217132 0.602514 -0.740552 -0.0201548 0.671697 -0.773792 -1.35159e-16 0.63344 -0.672952 -0.0766099 0.735709 -0.738222 -0.062058 0.671697 -0.736072 -0.0837956 0.671697 -0.670323 -0.0969512 0.735709 -0.599902 -0.0867659 0.795355 -0.645502 -0.205085 0.735708 -0.577689 -0.18354 0.795355 -0.652197 -0.182679 0.735708 -0.472002 -0.230806 0.850848 -0.533701 -0.287356 0.795355 -0.544528 -0.266271 0.795355 -0.608449 -0.297528 0.735708 -0.478971 -0.371481 0.795355 -0.444298 -0.412323 0.795355 -0.496453 -0.460725 0.735709 -0.425063 -0.432125 0.795355 -0.385122 -0.357406 0.850848 -0.404557 -0.451381 0.795355 -0.331801 -0.407388 0.850848 -0.335524 -0.504812 0.795355 -0.310103 -0.520814 0.795355 -0.283553 -0.535732 0.795355 -0.227337 -0.561898 0.795355 -0.254024 -0.627858 0.735708 -0.197058 -0.487058 0.850848 -0.136537 -0.590566 0.795355 -0.104971 -0.596986 0.795355 -0.0729594 -0.601737 0.795355 -0.0406351 -0.604781 0.795355 -0.00813583 -0.60609 0.795355 0.0243987 -0.605653 0.795355 0.0568277 -0.603474 0.795355 0.120818 -0.593981 0.795355 0.135001 -0.663708 0.735709 0.104726 -0.514869 0.850848 0.182777 -0.57793 0.795355 0.212692 -0.567603 0.795355 0.241756 -0.555846 0.795355 0.23393 -0.470462 0.850848 0.322958 -0.512942 0.795355 0.371429 -0.479011 0.795355 0.41503 -0.535241 0.735708 0.393828 -0.460772 0.795355 0.321958 -0.415211 0.850848 0.359699 -0.382981 0.850848 0.43484 -0.422286 0.795355 0.393045 -0.348673 0.850848 0.501717 -0.340133 0.795355 0.446735 -0.276559 0.850848 0.54954 -0.255766 0.795355 0.53925 -0.276804 0.795355 0.602551 -0.309297 0.735709 0.467427 -0.239936 0.850848 0.476347 -0.221701 0.850848 0.484367 -0.203584 0.850848 0.567052 -0.214155 0.795355 0.497869 -0.167882 0.850848 0.503435 -0.15037 0.850848 0.508267 -0.133125 0.850848 0.512407 -0.116174 0.850848 0.515897 -0.0995369 0.850848 0.518777 -0.0832325 0.850848 0.521087 -0.067275 0.850848 0.522864 -0.0516756 0.850848 0.524146 -0.036443 0.850848 0.524968 -0.0215831 0.850848 0.525364 -0.00709986 0.850848 0.525364 0.00709976 0.850848 0.524968 0.0215832 0.850848 0.524146 0.036443 0.850848 0.522864 0.0516756 0.850848 0.521087 0.0672749 0.850848 0.518777 0.0832325 0.850848 0.515897 0.0995369 0.850848 0.512407 0.116174 0.850848 0.586365 0.153581 0.795355 0.503435 0.15037 0.850848 0.497869 0.167882 0.850848 0.567052 0.214155 0.795355 0.484367 0.203584 0.850848 0.476347 0.221701 0.850848 0.486859 0.361081 0.795355 0.54401 0.403468 0.735708 0.470773 0.381816 0.795355 0.422014 0.312989 0.850848 0.393045 0.348673 0.850848 0.414969 0.441828 0.795355 0.371429 0.479011 0.795355 0.41503 0.535241 0.735709 0.347794 0.496437 0.795355 0.321958 0.415211 0.850848 0.322958 0.512942 0.795355 0.296965 0.528415 0.795355 0.269875 0.542751 0.795355 0.212693 0.567603 0.795355 0.23766 0.634232 0.735709 0.184364 0.492003 0.850848 0.152114 0.586747 0.795355 0.120818 0.593981 0.795355 0.0890127 0.599573 0.795355 0.0568279 0.603475 0.795355 0.0243986 0.605653 0.795355 -0.00813573 0.60609 0.795355 -0.0406349 0.604781 0.795355 -0.104971 0.596986 0.795355 -0.117294 0.667065 0.735708 -0.09099 0.517473 0.850848 -0.167532 0.582532 0.795355 -0.197835 0.572951 0.795355 -0.227337 0.561897 0.795355 -0.283553 0.535732 0.795355 -0.316839 0.59862 0.735709 -0.310103 0.520814 0.795355 -0.245787 0.464377 0.850848 -0.335523 0.504812 0.795355 -0.311847 0.422858 0.850848 -0.382785 0.469986 0.795355 -0.425063 0.432125 0.795355 -0.474961 0.482851 0.735708 -0.415176 0.322003 0.850848 -0.428585 0.303928 0.850848 -0.404557 0.451381 0.795355 -0.440942 0.285705 0.850848 -0.521771 0.30849 0.795355 -0.480467 0.212625 0.850848 -0.488051 0.194585 0.850848 -0.50594 0.141713 0.850848 -0.510421 0.124611 0.850848 -0.514231 0.107815 0.850848 -0.520001 0.0752097 0.850848 -0.604014 0.0507758 0.795355 -0.524613 0.0289662 0.850848 -0.602254 0.0685615 0.795355 -0.525217 0.0142943 0.850848 -0.8496 -0.0231227 0.52692 -0.812562 0 0.582874 -0.848651 -3.36275e-16 0.528953 -0.605222 -0.033417 0.795355 -0.604014 -0.0507759 0.795355 -0.602254 -0.0685616 0.795355 -0.596914 -0.105377 0.795355 -0.729545 -0.128792 0.671697 -0.662885 -0.138982 0.735708 -0.666985 -0.117747 0.735708 -0.657974 -0.160634 0.735708 -0.725061 -0.152018 0.671697 -0.58368 -0.163487 0.795355 -0.637834 -0.227818 0.735708 -0.629138 -0.250836 0.735708 -0.69766 -0.249186 0.671697 -0.688148 -0.274363 0.671697 -0.596352 -0.321088 0.735709 -0.535196 -0.415088 0.735709 -0.462263 -0.392076 0.795355 -0.474961 -0.482851 0.735709 -0.401996 -0.545098 0.735709 -0.427719 -0.525157 0.735709 -0.467837 -0.574414 0.671697 -0.382785 -0.469986 0.795355 -0.37491 -0.56407 0.735708 -0.346505 -0.581951 0.735708 -0.285983 -0.61396 0.735708 -0.312807 -0.671546 0.671697 -0.255939 -0.54946 0.795355 -0.221058 -0.640208 0.735708 -0.187198 -0.650915 0.735708 -0.152565 -0.659892 0.735708 -0.117293 -0.667065 0.735708 -0.0815239 -0.672374 0.735709 -0.0454052 -0.675775 0.735709 -0.00909088 -0.677237 0.735709 0.0634986 -0.674315 0.735709 0.0694545 -0.737563 0.671697 0.0994617 -0.669955 0.735709 0.108791 -0.732794 0.671697 0.0890127 -0.599573 0.795355 0.16997 -0.655624 0.735709 0.204232 -0.645772 0.735709 0.23766 -0.634232 0.735709 0.301555 -0.606463 0.735708 0.329839 -0.663347 0.671697 0.331825 -0.590445 0.735708 0.269875 -0.542751 0.795355 0.360869 -0.573155 0.735708 0.347794 -0.496437 0.795355 0.440059 -0.514861 0.735708 0.414969 -0.441828 0.795355 0.485885 -0.471857 0.735708 0.453439 -0.402249 0.795355 0.526036 -0.426637 0.735709 0.486858 -0.361081 0.795355 0.560613 -0.38006 0.735709 0.515379 -0.319054 0.795355 0.527877 -0.297921 0.795355 0.558792 -0.234866 0.795355 0.648968 -0.193839 0.735709 0.641793 -0.216413 0.735709 0.70199 -0.236712 0.671697 0.574369 -0.193678 0.795355 0.58079 -0.173475 0.795355 0.586365 -0.153581 0.795355 0.591142 -0.134025 0.795355 0.595168 -0.114831 0.795355 0.59849 -0.0960216 0.795355 0.601155 -0.0776122 0.795355 0.603206 -0.0596159 0.795355 0.604685 -0.0420427 0.795355 0.605633 -0.0248995 0.795355 0.606089 -0.00819079 0.795355 0.606089 0.00819068 0.795355 0.605633 0.0248996 0.795355 0.604684 0.0420427 0.795355 0.603205 0.0596159 0.795355 0.595168 0.114831 0.795355 0.591142 0.134024 0.795355 0.641793 0.216413 0.735709 0.648968 0.193839 0.735709 0.709838 0.21202 0.671697 0.58079 0.173475 0.795355 0.574369 0.193678 0.795355 0.61405 0.28579 0.735708 0.624388 0.262437 0.735708 0.682953 0.287052 0.671697 0.558792 0.234866 0.795355 0.54954 0.255766 0.795355 0.602551 0.309297 0.735708 0.527877 0.297921 0.795355 0.575878 0.356507 0.735708 0.501718 0.340133 0.795355 0.526036 0.426637 0.735708 0.453438 0.402249 0.795355 0.485884 0.471857 0.735709 0.463681 0.493693 0.735709 0.393828 0.460772 0.795355 0.388621 0.554713 0.735709 0.360869 0.573155 0.735709 0.331825 0.590445 0.735709 0.270136 0.621096 0.735709 0.295473 0.679352 0.671697 0.241756 0.555846 0.795355 0.204232 0.645772 0.735709 0.16997 0.655624 0.735708 0.135001 0.663708 0.735708 0.0994617 0.669956 0.735708 0.0634988 0.674315 0.735708 0.0272627 0.676749 0.735708 -0.00909077 0.677237 0.735708 -0.0815238 0.672374 0.735708 -0.0891704 0.73544 0.671697 -0.0729593 0.601737 0.795355 -0.152565 0.659891 0.735709 -0.187198 0.650915 0.735709 -0.221058 0.640208 0.735709 -0.254024 0.627857 0.735709 -0.255939 0.54946 0.795355 -0.346505 0.581951 0.735709 -0.427719 0.525157 0.735709 -0.401996 0.545098 0.735709 -0.439702 0.596226 0.671697 -0.359764 0.487833 0.795355 -0.49444 0.350629 0.795355 -0.452047 0.504368 0.735709 -0.508696 0.329605 0.795355 -0.544528 0.266271 0.795355 -0.554293 0.245296 0.795355 -0.563043 0.224484 0.795355 -0.58885 0.143759 0.795355 -0.58368 0.163488 0.795355 -0.652197 0.182679 0.735709 -0.645502 0.205085 0.735709 -0.637834 0.227818 0.735709 -0.596914 0.105377 0.795355 -0.593246 0.124381 0.795355 -0.599902 0.0867661 0.795355 -0.666985 0.117747 0.735709 -0.672952 0.0766098 0.735709 -0.674918 0.0567363 0.735709 -0.605222 0.033417 0.795355 -0.60592 0.0164907 0.795355 -0.676268 -0.0373398 0.735709 -0.674918 -0.0567363 0.735709 -0.792986 -0.0902749 0.602514 -0.846928 -0.0711962 0.52692 -0.844461 -0.0961348 0.52692 -0.713371 -0.199813 0.671697 -0.719689 -0.175701 0.671697 -0.775337 -0.189287 0.602514 -0.760641 -0.241666 0.602514 -0.706047 -0.224321 0.671697 -0.76853 -0.215263 0.602514 -0.619361 -0.27409 0.735708 -0.677454 -0.299799 0.671697 -0.741357 -0.295577 0.602514 -0.729836 -0.32298 0.602514 -0.621725 -0.402841 0.671697 -0.552481 -0.391788 0.735709 -0.516527 -0.438101 0.735709 -0.543018 -0.503939 0.671697 -0.51951 -0.528141 0.671697 -0.452047 -0.504368 0.735709 -0.439702 -0.596226 0.671697 -0.410075 -0.616978 0.671697 -0.373353 -0.705396 0.602514 -0.346557 -0.654768 0.671697 -0.316839 -0.59862 0.735708 -0.27785 -0.686748 0.671697 -0.241792 -0.700257 0.671697 -0.204756 -0.711968 0.671697 -0.166875 -0.721786 0.671697 -0.128295 -0.729632 0.671697 -0.0891705 -0.73544 0.671697 -0.049664 -0.739159 0.671697 0.0321257 -0.797461 0.602514 0.02982 -0.740225 0.671697 0.0272628 -0.676749 0.735709 0.147663 -0.72596 0.671697 0.185912 -0.717119 0.671697 0.223389 -0.706343 0.671697 0.31832 -0.731881 0.602514 0.295473 -0.679352 0.671697 0.270136 -0.621095 0.735709 0.362949 -0.645826 0.671697 0.453958 -0.585444 0.671697 0.425072 -0.606743 0.671697 0.45794 -0.653657 0.602514 0.388621 -0.554713 0.735708 0.531458 -0.516115 0.671697 0.507172 -0.539999 0.671697 0.546388 -0.581753 0.602514 0.463681 -0.493693 0.735708 0.506667 -0.449468 0.735708 0.575376 -0.466653 0.671697 0.54401 -0.403468 0.735709 0.645168 -0.364117 0.671697 0.629893 -0.389946 0.671697 0.678598 -0.420097 0.602514 0.575878 -0.356507 0.735709 0.589843 -0.332893 0.735709 0.659068 -0.338308 0.671697 0.61405 -0.28579 0.735709 0.624388 -0.262437 0.735709 0.633618 -0.239294 0.735709 0.655197 -0.171609 0.735709 0.660534 -0.149757 0.735708 0.665033 -0.128311 0.735708 0.668746 -0.107293 0.735708 0.671723 -0.0867229 0.735708 0.674015 -0.066614 0.735708 0.675667 -0.046978 0.735708 0.676727 -0.0278224 0.735708 0.677236 -0.0091523 0.735708 0.677236 0.00915217 0.735708 0.676727 0.0278226 0.735709 0.675667 0.046978 0.735709 0.674014 0.066614 0.735709 0.72741 0.140346 0.671697 0.731471 0.117357 0.671697 0.78803 0.126431 0.602514 0.668746 0.107293 0.735709 0.665033 0.128311 0.735709 0.660534 0.149757 0.735709 0.655197 0.171609 0.735709 0.633618 0.239294 0.735709 0.659068 0.338308 0.671697 0.589843 0.332893 0.735708 0.629893 0.389946 0.671697 0.560613 0.38006 0.735708 0.595036 0.441311 0.671697 0.531458 0.516115 0.671697 0.55419 0.491627 0.671697 0.597041 0.52964 0.602514 0.506667 0.449468 0.735708 0.453958 0.585444 0.671697 0.481334 0.563152 0.671697 0.518552 0.606696 0.602514 0.440059 0.514861 0.735709 0.425072 0.606743 0.671697 0.394717 0.626914 0.671697 0.329839 0.663347 0.671697 0.355343 0.714638 0.602514 0.301555 0.606463 0.735709 0.259952 0.693721 0.671697 0.223388 0.706343 0.671697 0.185912 0.717119 0.671697 0.147663 0.725961 0.671697 0.108791 0.732794 0.671697 0.0694547 0.737563 0.671697 -0.0107123 0.798036 0.602514 -0.0496637 0.739159 0.671697 -0.00994344 0.740759 0.671697 -0.0535038 0.796313 0.602514 -0.045405 0.675775 0.735708 -0.128295 0.729632 0.671697 -0.166875 0.721786 0.671697 -0.204756 0.711968 0.671697 -0.241792 0.700257 0.671697 -0.346557 0.654768 0.671697 -0.312807 0.671546 0.671697 -0.336994 0.723472 0.602514 -0.285983 0.61396 0.735709 -0.379005 0.636536 0.671697 -0.37491 0.56407 0.735709 -0.467837 0.574414 0.671697 -0.51951 0.528141 0.671697 -0.608661 0.516245 0.602514 -0.552481 0.391788 0.735708 -0.494447 0.551675 0.671697 -0.568411 0.368297 0.735708 -0.706047 0.224322 0.671697 -0.69766 0.249187 0.671697 -0.751604 0.268454 0.602514 -0.608449 0.297528 0.735708 -0.61936 0.27409 0.735709 -0.629138 0.250836 0.735709 -0.657974 0.160634 0.735709 -0.729545 0.128792 0.671697 -0.733197 0.106045 0.671697 -0.670323 0.0969513 0.735709 -0.662885 0.138982 0.735709 -0.736072 0.0837955 0.671697 -0.738222 0.0620579 0.671697 -0.677048 0.0184265 0.735708 -0.676268 0.0373398 0.735709 -0.936345 -0.0254835 0.350155 -0.940465 -8.88808e-16 0.339891 -0.964182 1.83511e-16 0.265241 -0.739699 -0.0408421 0.671697 -0.912879 -5.23527e-16 0.40823 -0.896009 -0.0243857 0.443367 -0.733197 -0.106045 0.671697 -0.841163 -0.12166 0.52692 -0.789889 -0.114244 0.602514 -0.836973 -0.147757 0.52692 -0.781124 -0.163772 0.602514 -0.785955 -0.13875 0.602514 -0.800393 -0.28588 0.52692 -0.751604 -0.268454 0.602514 -0.810015 -0.257354 0.52692 -0.665519 -0.325435 0.671697 -0.716978 -0.350599 0.602514 -0.64817 -0.549756 0.52692 -0.585006 -0.542904 0.602514 -0.60866 -0.516245 0.602514 -0.564975 -0.479193 0.671697 -0.567256 -0.632911 0.52692 -0.504011 -0.618829 0.602514 -0.532678 -0.594332 0.602514 -0.494447 -0.551675 0.671697 -0.4737 -0.642328 0.602514 -0.441783 -0.664684 0.602514 -0.379006 -0.636536 0.671697 -0.336994 -0.723472 0.602514 -0.299334 -0.739849 0.602514 -0.260488 -0.754402 0.602514 -0.220588 -0.767019 0.602514 -0.179778 -0.777597 0.602514 -0.138215 -0.786049 0.602514 -0.0569772 -0.848003 0.52692 -0.0107124 -0.798036 0.602514 -0.0535041 -0.796313 0.602514 -0.0114078 -0.849839 0.52692 -0.00994356 -0.740759 0.671697 0.0748249 -0.794593 0.602514 0.117203 -0.789456 0.602514 0.159081 -0.782093 0.602514 0.200288 -0.772568 0.602514 0.240661 -0.760959 0.602514 0.259951 -0.693721 0.671697 0.355343 -0.714638 0.602514 0.391013 -0.695763 0.602514 0.394717 -0.626914 0.671697 0.489059 -0.630712 0.602514 0.481334 -0.563152 0.671697 0.619865 -0.502736 0.602514 0.597041 -0.52964 0.602514 0.635796 -0.56402 0.52692 0.55419 -0.491626 0.671697 0.66061 -0.447852 0.602514 0.641045 -0.475435 0.602514 0.682657 -0.506296 0.52692 0.595036 -0.441311 0.671697 0.613196 -0.415708 0.671697 0.73576 -0.309248 0.602514 0.723578 -0.336767 0.602514 0.770547 -0.358627 0.52692 0.671645 -0.312596 0.671697 0.682952 -0.287052 0.671697 0.693048 -0.261739 0.671697 0.772065 -0.202219 0.602514 0.764725 -0.228414 0.602514 0.814364 -0.243241 0.52692 0.709838 -0.21202 0.671697 0.716652 -0.187705 0.671697 0.72249 -0.163804 0.671697 0.72741 -0.140346 0.671697 0.731471 -0.117357 0.671697 0.734728 -0.0948571 0.671697 0.737234 -0.0728621 0.671697 0.739042 -0.0513844 0.671697 0.740201 -0.030432 0.671697 0.740758 -0.0100107 0.671697 0.740758 0.0100106 0.671697 0.740201 0.0304322 0.671697 0.739042 0.0513844 0.671697 0.737234 0.0728621 0.671697 0.734728 0.094857 0.671697 0.72249 0.163804 0.671697 0.716652 0.187705 0.671697 0.764725 0.228414 0.602514 0.70199 0.236712 0.671697 0.693048 0.261739 0.671697 0.73576 0.309248 0.602514 0.671645 0.312596 0.671697 0.678598 0.420097 0.602514 0.695054 0.392271 0.602514 0.740171 0.417735 0.52692 0.645168 0.364117 0.671697 0.613196 0.415708 0.671697 0.641045 0.475435 0.602514 0.575376 0.466653 0.671697 0.572552 0.556023 0.602514 0.507172 0.539999 0.671697 0.489059 0.630712 0.602514 0.45794 0.653657 0.602514 0.416394 0.740926 0.52692 0.391013 0.695763 0.602514 0.362949 0.645826 0.671697 0.31832 0.731881 0.602514 0.280052 0.747361 0.602514 0.240661 0.760959 0.602514 0.200287 0.772568 0.602514 0.159081 0.782093 0.602514 0.117203 0.789456 0.602514 0.0342109 0.849226 0.52692 0.0321255 0.797461 0.602514 0.0298198 0.740226 0.671697 -0.0960653 0.792306 0.602514 -0.138215 0.786049 0.602514 -0.179778 0.777597 0.602514 -0.220588 0.767019 0.602514 -0.318765 0.787874 0.52692 -0.299334 0.739848 0.602514 -0.27785 0.686748 0.671697 -0.373354 0.705396 0.602514 -0.408311 0.685754 0.602514 -0.410075 0.616978 0.671697 -0.4737 0.642328 0.602514 -0.504011 0.618829 0.602514 -0.559679 0.568978 0.602514 -0.543018 0.503939 0.671697 -0.532678 0.594332 0.602514 -0.621725 0.402841 0.671697 -0.652287 0.351205 0.671697 -0.665519 0.325435 0.671697 -0.677454 0.299799 0.671697 -0.688148 0.274363 0.671697 -0.713371 0.199814 0.671697 -0.719689 0.175701 0.671697 -0.76064 0.241667 0.602514 -0.725061 0.152018 0.671697 -0.785955 0.13875 0.602514 -0.792986 0.0902748 0.602514 -0.795303 0.0668564 0.602514 -0.740552 0.0201549 0.671697 -0.739699 0.0408421 0.671697 -0.796894 -0.0440001 0.602514 -0.795303 -0.0668564 0.602514 -0.825666 -0.201574 0.52692 -0.831829 -0.174403 0.52692 -0.877266 -0.18393 0.443366 -0.818417 -0.229236 0.52692 -0.870766 -0.212584 0.443366 -0.789481 -0.314764 0.52692 -0.777211 -0.343945 0.52692 -0.832605 -0.331957 0.443366 -0.819665 -0.362733 0.443366 -0.693287 -0.491639 0.52692 -0.630659 -0.489128 0.602514 -0.622979 -0.578146 0.52692 -0.55968 -0.568978 0.602514 -0.536728 -0.658999 0.52692 -0.504449 -0.684022 0.52692 -0.458567 -0.770158 0.443366 -0.397589 -0.751185 0.52692 -0.434815 -0.730268 0.52692 -0.408311 -0.685754 0.602514 -0.358869 -0.770434 0.52692 -0.318764 -0.787874 0.52692 -0.277397 -0.803372 0.52692 -0.234907 -0.816807 0.52692 -0.155227 -0.882797 0.443366 -0.102301 -0.843736 0.52692 -0.147187 -0.837073 0.52692 -0.107889 -0.889824 0.443366 -0.0960654 -0.792306 0.602514 0.0342111 -0.849226 0.52692 0.079682 -0.846172 0.52692 0.124811 -0.840701 0.52692 0.169407 -0.832861 0.52692 0.213289 -0.822717 0.52692 0.31452 -0.839347 0.443367 0.338983 -0.779388 0.52692 0.29823 -0.795873 0.52692 0.280051 -0.747361 0.602514 0.378409 -0.761027 0.52692 0.416395 -0.740926 0.52692 0.425237 -0.675389 0.602514 0.487665 -0.696088 0.52692 0.520805 -0.671653 0.52692 0.518552 -0.606696 0.602514 0.581855 -0.619516 0.52692 0.572552 -0.556023 0.602514 0.722647 -0.447367 0.52692 0.695054 -0.392271 0.602514 0.710029 -0.364466 0.602514 0.746636 -0.281977 0.602514 0.75627 -0.255015 0.602514 0.778354 -0.17647 0.602514 0.783655 -0.151198 0.602514 0.78803 -0.126431 0.602514 0.791539 -0.102192 0.602514 0.794239 -0.078496 0.602514 0.796186 -0.0553575 0.602514 0.797435 -0.0327851 0.602514 0.798035 -0.0107848 0.602514 0.798035 0.0107846 0.602514 0.797435 0.0327853 0.602514 0.796186 0.0553575 0.602514 0.794239 0.078496 0.602514 0.791539 0.102192 0.602514 0.828879 0.187925 0.52692 0.834524 0.161013 0.52692 0.880109 0.169808 0.443367 0.783655 0.151198 0.602514 0.778354 0.17647 0.602514 0.772065 0.202219 0.602514 0.795102 0.300281 0.52692 0.805361 0.271569 0.52692 0.849352 0.286403 0.443367 0.75627 0.255015 0.602514 0.746636 0.281977 0.602514 0.812637 0.378216 0.443366 0.756118 0.388125 0.52692 0.770547 0.358627 0.52692 0.723578 0.336766 0.602514 0.710029 0.364467 0.602514 0.741919 0.502974 0.443366 0.682657 0.506296 0.52692 0.703491 0.476923 0.52692 0.66061 0.447852 0.602514 0.619866 0.502736 0.602514 0.635796 0.56402 0.52692 0.613638 0.653356 0.443366 0.552212 0.646078 0.52692 0.581855 0.619516 0.52692 0.546388 0.581753 0.602514 0.520805 0.671653 0.52692 0.487665 0.696088 0.52692 0.425238 0.675389 0.602514 0.378409 0.761027 0.52692 0.338983 0.779388 0.52692 0.29823 0.795873 0.52692 0.256283 0.810355 0.52692 0.213288 0.822717 0.52692 0.131628 0.886623 0.443366 0.0796821 0.846172 0.52692 0.124811 0.840701 0.52692 0.0840346 0.892393 0.443366 0.074825 0.794593 0.602514 -0.0114076 0.849839 0.52692 -0.0569769 0.848003 0.52692 -0.102301 0.843736 0.52692 -0.147187 0.837073 0.52692 -0.191448 0.828072 0.52692 -0.292549 0.847255 0.443366 -0.277397 0.803372 0.52692 -0.260488 0.754402 0.602514 -0.358869 0.770434 0.52692 -0.397589 0.751185 0.52692 -0.496158 0.746494 0.443367 -0.504449 0.684022 0.52692 -0.47046 0.70783 0.52692 -0.441783 0.664684 0.602514 -0.598241 0.667483 0.443367 -0.596009 0.605911 0.52692 -0.567256 0.632911 0.52692 -0.585006 0.542904 0.602514 -0.64817 0.549756 0.52692 -0.771573 0.456182 0.443366 -0.702723 0.378361 0.602514 -0.716978 0.350598 0.602514 -0.729836 0.32298 0.602514 -0.741357 0.295577 0.602514 -0.73161 0.432554 0.52692 -0.781124 0.163772 0.602514 -0.775337 0.189287 0.602514 -0.825666 0.201574 0.52692 -0.76853 0.215264 0.602514 -0.810015 0.257354 0.52692 -0.800393 0.28588 0.52692 -0.789889 0.114245 0.602514 -0.836973 0.147757 0.52692 -0.844461 0.0961347 0.52692 -0.846928 0.0711962 0.52692 -0.797813 0.0217133 0.602514 -0.796894 0.0440001 0.602514 -0.882137 -1.72353e-16 0.470993 -0.848623 -0.0468562 0.52692 -0.991288 -0.0269788 0.128917 -0.96899 -0.026372 0.245688 -0.982976 -5.50413e-16 0.183733 -0.930681 -0.10595 0.350155 -0.965942 -0.081201 0.245689 -0.963128 -0.109644 0.245689 -0.959366 -0.138756 0.245689 -0.927046 -0.134082 0.350155 -0.892718 -0.28363 0.350155 -0.854261 -0.271411 0.443366 -0.901978 -0.252642 0.350155 -0.844113 -0.301496 0.443366 -0.882113 -0.315069 0.350154 -0.771573 -0.456181 0.443366 -0.713276 -0.462161 0.52692 -0.731156 -0.518495 0.443366 -0.671597 -0.520878 0.52692 -0.683575 -0.579786 0.443367 -0.657009 -0.609726 0.443367 -0.596009 -0.605911 0.52692 -0.598241 -0.667483 0.443367 -0.566046 -0.694995 0.443367 -0.518494 -0.7801 0.350155 -0.496158 -0.746494 0.443367 -0.47046 -0.70783 0.52692 -0.419306 -0.792217 0.443366 -0.378472 -0.812518 0.443366 -0.336176 -0.83091 0.443366 -0.29255 -0.847255 0.443366 -0.210995 -0.912619 0.350154 -0.201906 -0.873304 0.443366 -0.191448 -0.828072 0.52692 -0.0600895 -0.894324 0.443366 -0.0120309 -0.89626 0.443366 0.0360798 -0.895614 0.443366 0.0840345 -0.892393 0.443366 0.131628 -0.886623 0.443367 0.17866 -0.878354 0.443367 0.28245 -0.893092 0.350155 0.270282 -0.854619 0.443367 0.256283 -0.810355 0.52692 0.357499 -0.821961 0.443367 0.399079 -0.802597 0.443367 0.499076 -0.792663 0.350155 0.514303 -0.734111 0.443366 0.477576 -0.758516 0.443366 0.45284 -0.71923 0.52692 0.608594 -0.712043 0.350154 0.613638 -0.653356 0.443366 0.582376 -0.681369 0.443366 0.552212 -0.646078 0.52692 0.609718 -0.592115 0.52692 0.670526 -0.594829 0.443366 0.660102 -0.53537 0.52692 0.719946 -0.533952 0.443366 0.703491 -0.476923 0.52692 0.76212 -0.471804 0.443366 0.740171 -0.417735 0.52692 0.756118 -0.388125 0.52692 0.812637 -0.378216 0.443367 0.78352 -0.329322 0.52692 0.795102 -0.300281 0.52692 0.805361 -0.271569 0.52692 0.874155 -0.19819 0.443367 0.867092 -0.227109 0.443367 0.906126 -0.237333 0.350155 0.822181 -0.215346 0.52692 0.828879 -0.187925 0.52692 0.834524 -0.161013 0.52692 0.839183 -0.134638 0.52692 0.842919 -0.108825 0.52692 0.845794 -0.0835913 0.52692 0.847868 -0.0589509 0.52692 0.849198 -0.0349133 0.52692 0.849838 -0.0114849 0.52692 0.849838 0.0114847 0.52692 0.849198 0.0349134 0.52692 0.847868 0.0589509 0.52692 0.845794 0.0835913 0.52692 0.842919 0.108825 0.52692 0.839183 0.134638 0.52692 0.822181 0.215346 0.52692 0.814364 0.243241 0.52692 0.78352 0.329321 0.52692 0.780602 0.440553 0.443366 0.722647 0.447367 0.52692 0.727499 0.590031 0.350154 0.670526 0.594829 0.443366 0.696159 0.564614 0.443366 0.660102 0.53537 0.52692 0.609717 0.592115 0.52692 0.582376 0.681369 0.443366 0.549253 0.708341 0.443366 0.499076 0.792663 0.350154 0.439139 0.781398 0.443367 0.477576 0.758516 0.443367 0.452841 0.719229 0.52692 0.399079 0.802597 0.443367 0.357499 0.821961 0.443367 0.314521 0.839347 0.443367 0.270282 0.854619 0.443367 0.186703 0.917896 0.350155 0.17866 0.878355 0.443366 0.169407 0.832861 0.52692 0.0360796 0.895614 0.443366 -0.0120308 0.89626 0.443366 -0.0600892 0.894324 0.443366 -0.107889 0.889824 0.443366 -0.155227 0.882797 0.443366 -0.258891 0.900204 0.350154 -0.247739 0.861424 0.443366 -0.234907 0.816807 0.52692 -0.336177 0.83091 0.443366 -0.378472 0.812518 0.443366 -0.419306 0.792217 0.443367 -0.434815 0.730268 0.52692 -0.532004 0.721386 0.443367 -0.536728 0.658998 0.52692 -0.686586 0.637174 0.350155 -0.683575 0.579785 0.443366 -0.657009 0.609726 0.443367 -0.62298 0.578145 0.52692 -0.628565 0.639008 0.443367 -0.748338 0.402921 0.52692 -0.763519 0.373356 0.52692 -0.777211 0.343945 0.52692 -0.78948 0.314764 0.52692 -0.818417 0.229237 0.52692 -0.844113 0.301496 0.443366 -0.854261 0.271411 0.443366 -0.831829 0.174403 0.52692 -0.841163 0.12166 0.52692 -0.882691 0.155828 0.443367 -0.890588 0.101386 0.443367 -0.89319 0.0750851 0.443367 -0.8496 0.0231228 0.52692 -0.848623 0.0468562 0.52692 -1 -3.68545e-16 -2.04623e-07 -0.99963 -0.0272059 -2.04623e-07 -0.99546 2.74273e-19 0.0951823 -0.894977 -0.0494157 0.443367 -0.89319 -0.0750852 0.443367 -0.890588 -0.101386 0.443367 -0.88711 -0.128306 0.443367 -0.882691 -0.155828 0.443367 -0.954588 -0.16852 0.245689 -0.916759 -0.19221 0.350155 -0.922428 -0.162843 0.350155 -0.909967 -0.222154 0.350155 -0.948721 -0.198911 0.245689 -0.863122 -0.241758 0.443366 -0.870087 -0.346902 0.350154 -0.912867 -0.326053 0.245689 -0.900422 -0.358996 0.245689 -0.89085 -0.435621 0.128917 -0.813509 -0.527106 0.245689 -0.764072 -0.541836 0.350154 -0.786102 -0.509348 0.350154 -0.752238 -0.487406 0.443366 -0.708282 -0.54933 0.443366 -0.714348 -0.605886 0.350154 -0.679763 -0.691056 0.245689 -0.625173 -0.697532 0.350155 -0.656862 -0.667775 0.350155 -0.628566 -0.639008 0.443367 -0.591528 -0.726283 0.350155 -0.532004 -0.721386 0.443367 -0.47921 -0.804829 0.350155 -0.438183 -0.827881 0.350155 -0.39551 -0.849096 0.350155 -0.35131 -0.868316 0.350155 -0.267917 -0.931589 0.245689 -0.258891 -0.900204 0.350154 -0.247739 -0.861424 0.443366 -0.162215 -0.922539 0.350154 -0.112746 -0.929882 0.350154 -0.0627946 -0.934585 0.350154 -0.0125725 -0.936608 0.350154 0.037704 -0.935933 0.350154 0.0878175 -0.932566 0.350154 0.137554 -0.926537 0.350154 0.243261 -0.938329 0.245689 0.235066 -0.906717 0.350155 0.224939 -0.867657 0.443367 0.328679 -0.877133 0.350155 0.373593 -0.858964 0.350155 0.417045 -0.838728 0.350155 0.43914 -0.781398 0.443367 0.537456 -0.767159 0.350155 0.549253 -0.708341 0.443366 0.641263 -0.682769 0.350154 0.643022 -0.624458 0.443366 0.696159 -0.564614 0.443366 0.700712 -0.621607 0.350154 0.752356 -0.557989 0.350154 0.741919 -0.502974 0.443366 0.844183 -0.476436 0.245689 0.833318 -0.427752 0.350154 0.815743 -0.460386 0.350154 0.780602 -0.440553 0.443366 0.79742 -0.409325 0.443367 0.893623 -0.375599 0.245688 0.876282 -0.33094 0.350155 0.863517 -0.362945 0.350155 0.826318 -0.34731 0.443367 0.838533 -0.316683 0.443367 0.849353 -0.286403 0.443367 0.858848 -0.256527 0.443367 0.880109 -0.169808 0.443366 0.885022 -0.141993 0.443366 0.888962 -0.11477 0.443366 0.891995 -0.0881574 0.443366 0.894182 -0.062171 0.443366 0.895584 -0.0368203 0.443366 0.896259 -0.0121122 0.443366 0.896259 0.012112 0.443366 0.895584 0.0368205 0.443366 0.894182 0.062171 0.443366 0.891995 0.0881574 0.443366 0.888962 0.114769 0.443366 0.885022 0.141993 0.443367 0.945356 0.214333 0.245688 0.906126 0.237333 0.350155 0.913508 0.207112 0.350155 0.874155 0.19819 0.443367 0.867092 0.227109 0.443367 0.858848 0.256527 0.443367 0.887589 0.299296 0.350155 0.838533 0.316683 0.443367 0.826318 0.34731 0.443367 0.79742 0.409326 0.443366 0.84922 0.395243 0.350155 0.815743 0.460386 0.350155 0.76212 0.471804 0.443366 0.719946 0.533952 0.443366 0.775318 0.525617 0.350154 0.700711 0.621607 0.350154 0.643022 0.624459 0.443366 0.641263 0.682769 0.350154 0.608594 0.712043 0.350154 0.556194 0.793905 0.245689 0.537456 0.767159 0.350154 0.514304 0.73411 0.443366 0.458909 0.816575 0.350155 0.417045 0.838728 0.350155 0.373593 0.858964 0.350155 0.292297 0.924229 0.245689 0.235065 0.906717 0.350155 0.28245 0.893092 0.350155 0.243261 0.938329 0.245689 0.224939 0.867657 0.443367 0.137554 0.926537 0.350155 0.0878177 0.932566 0.350155 0.0377038 0.935933 0.350155 -0.0125724 0.936608 0.350154 -0.0627943 0.934585 0.350154 -0.112746 0.929882 0.350154 -0.218351 0.944436 0.245689 -0.210995 0.912619 0.350154 -0.201906 0.873304 0.443366 -0.305719 0.885397 0.350154 -0.351311 0.868316 0.350154 -0.39551 0.849096 0.350154 -0.495918 0.832888 0.245688 -0.518494 0.7801 0.350155 -0.47921 0.804829 0.350155 -0.458567 0.770158 0.443367 -0.555954 0.753861 0.350155 -0.566046 0.694995 0.443367 -0.625173 0.697532 0.350155 -0.765972 0.594074 0.245689 -0.740167 0.57406 0.350155 -0.834419 0.493338 0.245689 -0.656862 0.667775 0.350155 -0.805225 0.39375 0.443366 -0.819665 0.362733 0.443366 -0.832605 0.331957 0.443366 -0.870766 0.212584 0.443367 -0.863122 0.241758 0.443366 -0.901978 0.252642 0.350154 -0.892718 0.28363 0.350154 -0.882113 0.315069 0.350154 -0.877266 0.18393 0.443367 -0.88711 0.128306 0.443367 -0.922428 0.162843 0.350155 -0.930681 0.10595 0.350155 -0.9334 0.0784653 0.350155 -0.894977 0.0494157 0.443367 -0.896009 0.0243858 0.443367 -0.935267 -0.0516403 0.350155 -0.9334 -0.0784654 0.350155 -0.933424 -0.26145 0.245689 -0.941692 -0.2299 0.245689 -0.963362 -0.23519 0.128917 -0.945101 -0.300272 0.128917 -0.923842 -0.293518 0.245689 -0.954904 -0.267466 0.128917 -0.856565 -0.379062 0.350154 -0.765972 -0.594074 0.245689 -0.808906 -0.57363 0.128917 -0.783599 -0.607745 0.128917 -0.740167 -0.57406 0.350154 -0.686586 -0.637174 0.350155 -0.739253 -0.62701 0.245689 -0.646969 -0.721851 0.245689 -0.575337 -0.780144 0.245689 -0.626238 -0.7689 0.128917 -0.588576 -0.798097 0.128917 -0.555954 -0.753861 0.350155 -0.536571 -0.807297 0.245689 -0.495918 -0.832888 0.245689 -0.45346 -0.856745 0.245689 -0.409299 -0.878699 0.245689 -0.316378 -0.916265 0.245689 -0.371925 -0.919267 0.128917 -0.323659 -0.93735 0.128917 -0.30572 -0.885397 0.350154 -0.218351 -0.944436 0.245689 -0.16787 -0.954702 0.245689 -0.116677 -0.962301 0.245689 -0.0649839 -0.967168 0.245689 -0.0130109 -0.969261 0.245689 0.0390185 -0.968563 0.245689 0.0908792 -0.965079 0.245689 0.193213 -0.949898 0.245688 0.145625 -0.980905 0.128917 0.197659 -0.971757 0.128917 0.186703 -0.917896 0.350155 0.292297 -0.924229 0.245689 0.340139 -0.907713 0.245689 0.386618 -0.888911 0.245689 0.474908 -0.845044 0.245689 0.441516 -0.887944 0.128917 0.485837 -0.86449 0.128917 0.458909 -0.816575 0.350155 0.516475 -0.820299 0.245689 0.57398 -0.740229 0.350155 0.556194 -0.793905 0.245689 0.629812 -0.736868 0.245689 0.695398 -0.675322 0.245689 0.678891 -0.722833 0.128917 0.7114 -0.690862 0.128917 0.67197 -0.65257 0.350154 0.727499 -0.590031 0.350154 0.725141 -0.643279 0.245689 0.778586 -0.577443 0.245689 0.775318 -0.525617 0.350154 0.79643 -0.493043 0.350154 0.84922 -0.395243 0.350155 0.887589 -0.299296 0.350155 0.897512 -0.268076 0.350155 0.991769 -0.128042 1.91753e-07 0.979134 -0.157092 -0.128917 0.983493 -0.126974 -0.128917 0.913508 -0.207112 0.350155 0.91973 -0.177452 0.350155 0.924864 -0.148385 0.350155 0.928982 -0.119936 0.350155 0.93215 -0.092126 0.350155 0.934436 -0.0649698 0.350154 0.935901 -0.0384779 0.350154 0.936606 -0.0126575 0.350154 0.936606 0.0126573 0.350154 0.935901 0.0384781 0.350154 0.934436 0.0649698 0.350154 0.932151 0.0921261 0.350154 0.928982 0.119936 0.350154 0.924864 0.148385 0.350154 0.91973 0.177452 0.350154 0.897512 0.268076 0.350155 0.906833 0.342478 0.245689 0.939671 0.316858 0.128917 0.927701 0.350359 0.128917 0.876282 0.33094 0.350155 0.863517 0.362945 0.350155 0.833318 0.427753 0.350155 0.878828 0.409022 0.245689 0.79643 0.493043 0.350155 0.844183 0.476436 0.245689 0.752356 0.557989 0.350154 0.802349 0.543942 0.245689 0.752863 0.610602 0.245689 0.695398 0.675322 0.245689 0.741828 0.658082 0.128917 0.7114 0.690862 0.128917 0.67197 0.65257 0.350154 0.66362 0.706573 0.245689 0.57398 0.740229 0.350154 0.629812 0.736868 0.245689 0.516476 0.820299 0.245689 0.474908 0.845044 0.245688 0.431585 0.86797 0.245689 0.340139 0.907713 0.245689 0.395515 0.909367 0.128917 0.347966 0.928601 0.128917 0.32868 0.877132 0.350155 0.193213 0.949898 0.245689 0.14235 0.95884 0.245689 0.0908794 0.965079 0.245689 0.0390183 0.968563 0.245689 -0.0130107 0.969261 0.245689 -0.0649835 0.967168 0.245689 -0.16787 0.954702 0.245689 -0.119362 0.984446 0.128917 -0.171733 0.976672 0.128917 -0.162215 0.922539 0.350154 -0.267917 0.931589 0.245689 -0.316378 0.916265 0.245689 -0.363559 0.898589 0.245689 -0.45346 0.856745 0.245689 -0.418718 0.898919 0.128917 -0.463894 0.87646 0.128917 -0.438183 0.827881 0.350154 -0.536571 0.807297 0.245689 -0.612151 0.751604 0.245689 -0.588576 0.798097 0.128917 -0.626238 0.7689 0.128917 -0.591528 0.726283 0.350155 -0.646969 0.721851 0.245689 -0.714348 0.605886 0.350155 -0.786102 0.509348 0.350155 -0.923842 0.293518 0.245689 -0.912867 0.326053 0.245689 -0.933874 0.333556 0.128917 -0.841474 0.411476 0.350154 -0.856565 0.379062 0.350154 -0.870087 0.346902 0.350154 -0.948721 0.198911 0.245689 -0.954588 0.16852 0.245688 -0.909967 0.222154 0.350154 -0.916759 0.19221 0.350155 -0.927046 0.134082 0.350155 -0.935267 0.0516403 0.350155 -0.936345 0.0254836 0.350155 -0.940459 -5.34075e-16 -0.339908 -0.936345 -0.0254835 -0.350155 -0.964178 -3.5318e-16 -0.265255 -0.967875 -0.0534406 0.245689 -0.96899 -0.026372 -0.245689 -0.991288 -0.0269788 -0.128917 -0.982975 -5.4829e-16 -0.183742 -0.993582 -0.113111 1.91753e-07 -0.985291 -0.112167 0.128917 -0.996485 -0.0837686 -2.04623e-07 -0.989702 -0.143144 1.91753e-07 -0.981443 -0.14195 0.128917 -0.984772 -0.173849 1.91753e-07 -0.970553 -0.203488 0.128917 -0.976555 -0.172398 0.128917 -0.941732 -0.336363 1.91753e-07 -0.933874 -0.333556 0.128917 -0.953054 -0.302799 1.91753e-07 -0.873139 -0.470116 0.128917 -0.834419 -0.493338 0.245689 -0.85362 -0.504691 0.128917 -0.832229 -0.539235 0.128917 -0.79071 -0.560727 0.245689 -0.73299 -0.680239 -2.04623e-07 -0.726874 -0.674563 0.128917 -0.762629 -0.646836 -2.04623e-07 -0.710523 -0.659389 0.245688 -0.695406 -0.706959 0.128917 -0.661857 -0.738462 0.128917 -0.612151 -0.751604 0.245689 -0.548918 -0.825875 0.128917 -0.50733 -0.852055 0.128917 -0.422241 -0.906483 1.91753e-07 -0.418718 -0.898919 0.128917 -0.467798 -0.883835 1.91753e-07 -0.375054 -0.927003 1.91753e-07 -0.363558 -0.898589 0.245689 -0.274083 -0.953026 0.128917 -0.223376 -0.96617 0.128917 -0.171733 -0.976672 0.128917 -0.119362 -0.984446 0.128917 -0.0664793 -0.989425 0.128917 -0.0133103 -0.991566 0.128917 0.0937528 -0.995596 -2.04623e-07 0.0929705 -0.987288 0.128917 0.0402523 -0.99919 -2.04623e-07 0.146851 -0.989159 -2.04623e-07 0.14235 -0.95884 0.245689 0.248859 -0.959922 0.128917 0.299024 -0.945497 0.128917 0.347966 -0.928601 0.128917 0.445232 -0.895415 1.91753e-07 0.398843 -0.917019 1.91753e-07 0.431585 -0.86797 0.245689 0.528361 -0.839175 0.128917 0.612773 -0.790259 1.91753e-07 0.60766 -0.783664 0.128917 0.573781 -0.819009 1.91753e-07 0.593991 -0.766037 0.245689 0.644305 -0.753825 0.128917 0.66362 -0.706573 0.245689 0.776668 -0.62991 -2.04623e-07 0.770187 -0.624653 0.128917 0.74807 -0.663619 1.91753e-07 0.752863 -0.610602 0.245689 0.82772 -0.561142 -2.04623e-07 0.820813 -0.556459 0.128917 0.803206 -0.595702 -2.04623e-07 0.802349 -0.543942 0.245689 0.824196 -0.510233 0.245689 0.843163 -0.521974 0.128917 0.86361 -0.4874 0.128917 0.862371 -0.442666 0.245689 0.878827 -0.409023 0.245688 0.899051 -0.418435 0.128917 0.914187 -0.384242 0.128917 0.906833 -0.342478 0.245689 0.918534 -0.309731 0.245689 0.928802 -0.277422 0.245689 0.937718 -0.245607 0.245689 0.945356 -0.214333 0.245689 0.951795 -0.183639 0.245689 0.957109 -0.153558 0.245689 0.96137 -0.124118 0.245689 0.964649 -0.0953379 0.245689 0.967014 -0.0672349 0.245689 0.968531 -0.0398194 0.245689 0.96926 -0.0130988 0.245689 0.96926 0.0130986 0.245689 0.968531 0.0398196 0.245689 0.967014 0.0672349 0.245689 0.964649 0.095338 0.245689 0.96137 0.124118 0.245689 0.957109 0.153558 0.245689 0.951795 0.183639 0.245689 0.967369 0.253373 -2.04623e-07 0.959296 0.251259 0.128917 0.975249 0.22111 -2.04623e-07 0.937718 0.245607 0.245689 0.928802 0.277422 0.245689 0.918534 0.309731 0.245689 0.893623 0.375599 0.245689 0.88964 0.456663 1.91753e-07 0.882216 0.452852 0.128917 0.906616 0.421956 1.91753e-07 0.862371 0.442666 0.245689 0.850258 0.526366 1.91753e-07 0.843163 0.521974 0.128917 0.870877 0.491502 1.91753e-07 0.824196 0.510233 0.245689 0.803206 0.595702 1.91753e-07 0.796503 0.590731 0.128917 0.82772 0.561142 1.91753e-07 0.778586 0.577443 0.245689 0.770187 0.624653 0.128917 0.725141 0.643279 0.245689 0.678891 0.722833 0.128917 0.612773 0.790259 -2.04623e-07 0.60766 0.783664 0.128917 0.649726 0.760168 -2.04623e-07 0.593991 0.766036 0.245689 0.568993 0.812174 0.128917 0.528361 0.839175 0.128917 0.485837 0.86449 0.128917 0.398843 0.917019 -2.04623e-07 0.445232 0.895415 -2.04623e-07 0.386618 0.888911 0.245689 0.299024 0.945497 0.128917 0.248859 0.959922 0.128917 0.197659 0.971757 0.128917 0.145625 0.980905 0.128917 0.0929707 0.987288 0.128917 0.0399162 0.990852 0.128917 -0.0133101 0.991566 0.128917 -0.120366 0.99273 1.91753e-07 -0.0670383 0.99775 1.91753e-07 -0.116677 0.962301 0.245689 -0.223376 0.96617 0.128917 -0.274083 0.953026 0.128917 -0.323658 0.93735 0.128917 -0.371925 0.919267 0.128917 -0.409299 0.878699 0.245689 -0.50733 0.852055 0.128917 -0.548918 0.825875 0.128917 -0.575337 0.780144 0.245689 -0.661857 0.738462 0.128917 -0.726874 0.674562 0.128917 -0.739254 0.62701 0.245689 -0.756265 0.641438 0.128917 -0.783599 0.607744 0.128917 -0.79071 0.560727 0.245689 -0.853498 0.459541 0.245689 -0.870812 0.425822 0.245689 -0.886428 0.392278 0.245689 -0.900422 0.358996 0.245689 -0.933424 0.26145 0.245689 -0.941692 0.2299 0.245689 -0.945101 0.300273 0.128917 -0.959366 0.138757 0.245689 -0.963128 0.109644 0.245689 -0.976555 0.172398 0.128917 -0.965942 0.0812009 0.245689 -0.985291 0.112167 0.128917 -0.98817 0.0830695 0.128917 -0.96899 0.0263721 0.245689 -0.967875 0.0534407 0.245689 -0.990147 -0.0546704 0.128917 -0.98817 -0.0830696 0.128917 -0.971468 -0.237169 1.91753e-07 -0.97872 -0.205201 1.91753e-07 -0.970553 -0.203488 -0.128917 -0.96294 -0.269717 1.91753e-07 -0.963362 -0.23519 -0.128917 -0.933874 -0.333556 -0.128917 -0.898347 -0.439287 1.91753e-07 -0.880486 -0.474072 -2.04623e-07 -0.860803 -0.508938 -2.04623e-07 -0.839232 -0.543773 -2.04623e-07 -0.815713 -0.578457 -2.04623e-07 -0.790192 -0.612859 -2.04623e-07 -0.756265 -0.641439 0.128917 -0.701258 -0.712908 -2.04623e-07 -0.626238 -0.7689 -0.128917 -0.631507 -0.77537 -2.04623e-07 -0.661857 -0.738462 -0.128917 -0.593529 -0.804813 1.91753e-07 -0.553538 -0.832824 1.91753e-07 -0.463894 -0.87646 -0.128917 -0.50733 -0.852055 -0.128917 -0.463894 -0.87646 0.128917 -0.326382 -0.945238 1.91753e-07 -0.276389 -0.961046 1.91753e-07 -0.225256 -0.9743 1.91753e-07 -0.173178 -0.98489 1.91753e-07 -0.120366 -0.99273 -2.04623e-07 -0.0133103 -0.991566 -0.128917 -0.0134223 -0.99991 -2.04623e-07 -0.0664793 -0.989425 -0.128917 0.0399164 -0.990852 -0.128917 0.0399164 -0.990852 0.128917 0.199322 -0.979934 -2.04623e-07 0.250953 -0.967999 -2.04623e-07 0.30154 -0.953454 -2.04623e-07 0.395515 -0.909367 -0.128917 0.347966 -0.928601 -0.128917 0.395515 -0.909367 0.128917 0.489925 -0.871765 1.91753e-07 0.532807 -0.846237 1.91753e-07 0.568993 -0.812174 0.128917 0.649727 -0.760168 1.91753e-07 0.684604 -0.728915 1.91753e-07 0.717386 -0.696676 1.91753e-07 0.741828 -0.658082 0.128917 0.796503 -0.590731 0.128917 0.882216 -0.452852 -0.128917 0.88964 -0.456663 -2.04623e-07 0.86361 -0.4874 -0.128917 0.882216 -0.452852 0.128917 0.927701 -0.350359 -0.128917 0.935507 -0.353307 -2.04623e-07 0.914187 -0.384242 -0.128917 0.927701 -0.350359 0.128917 0.939671 -0.316858 0.128917 0.950176 -0.283806 0.128917 0.959296 -0.251259 0.128917 0.967111 -0.219265 0.128917 0.973698 -0.187865 0.128917 0.979134 -0.157092 0.128917 0.983493 -0.126974 0.128917 0.986847 -0.0975318 0.128917 0.989267 -0.0687821 0.128917 0.990818 -0.0407357 0.128917 0.991565 -0.0134002 0.128917 0.991565 0.0134 0.128917 0.990818 0.040736 0.128917 0.989267 0.0687822 0.128917 0.986847 0.0975319 0.128917 0.983493 0.126974 0.128917 0.979134 0.157092 0.128917 0.973698 0.187865 0.128917 0.967111 0.219265 0.128917 0.950176 0.283806 0.128917 0.947578 0.319525 1.91753e-07 0.935507 0.353307 1.91753e-07 0.914187 0.384242 0.128917 0.899051 0.418435 0.128917 0.86361 0.4874 0.128917 0.820813 0.556459 0.128917 0.776668 0.62991 1.91753e-07 0.74807 0.663619 1.91753e-07 0.717386 0.696676 -2.04623e-07 0.684604 0.728915 -2.04623e-07 0.644305 0.753825 0.128917 0.573781 0.819008 -2.04623e-07 0.532807 0.846237 -2.04623e-07 0.441516 0.887944 -0.128917 0.485837 0.86449 -0.128917 0.441516 0.887944 0.128917 0.350894 0.936415 -2.04623e-07 0.30154 0.953454 1.91753e-07 0.250953 0.967999 1.91753e-07 0.199322 0.979934 1.91753e-07 0.146851 0.989159 1.91753e-07 0.093753 0.995596 1.91753e-07 -0.0133101 0.991566 -0.128917 -0.0134221 0.99991 1.91753e-07 0.0399162 0.990852 -0.128917 -0.0664789 0.989425 -0.128917 -0.0664789 0.989425 0.128917 -0.173179 0.98489 1.91753e-07 -0.225256 0.9743 -2.04623e-07 -0.276389 0.961046 -2.04623e-07 -0.326382 0.945238 -2.04623e-07 -0.418718 0.898919 -0.128917 -0.422242 0.906483 -2.04623e-07 -0.371925 0.919267 -0.128917 -0.467798 0.883835 -2.04623e-07 -0.511599 0.859225 -2.04623e-07 -0.588576 0.798097 -0.128917 -0.593529 0.804813 -2.04623e-07 -0.548918 0.825875 -0.128917 -0.631508 0.77537 -2.04623e-07 -0.695406 0.706959 -0.128917 -0.701258 0.712908 1.91753e-07 -0.661857 0.738462 -0.128917 -0.732991 0.680239 1.91753e-07 -0.762629 0.646836 1.91753e-07 -0.790193 0.612859 1.91753e-07 -0.834419 0.493338 -0.245689 -0.853498 0.459541 -0.245689 -0.890851 0.435621 0.128917 -0.906827 0.401305 0.128917 -0.921142 0.367257 0.128917 -0.970553 0.203488 0.128917 -0.963362 0.23519 0.128917 -0.971468 0.237169 -2.04623e-07 -0.954904 0.267467 0.128917 -0.953054 0.302799 -2.04623e-07 -0.941732 0.336363 -2.04623e-07 -0.981443 0.14195 0.128917 -0.984772 0.173849 -2.04623e-07 -0.993582 0.113111 -2.04623e-07 -0.996485 0.0837686 1.91753e-07 -0.991288 0.0269789 0.128917 -0.990147 0.0546704 0.128917 -0.99546 -3.67164e-16 -0.0951771 -0.998479 -0.0551305 -2.04623e-07 -0.896009 -0.0243857 -0.443366 -0.91287 -9.5769e-18 -0.408251 -0.963128 -0.109644 -0.245689 -0.9334 -0.0784654 -0.350155 -0.930681 -0.10595 -0.350155 -0.927046 -0.134082 -0.350155 -0.959366 -0.138756 -0.245689 -0.892718 -0.28363 -0.350154 -0.923842 -0.293518 -0.245689 -0.901978 -0.252642 -0.350154 -0.85362 -0.504691 -0.128917 -0.853498 -0.459541 -0.245689 -0.834419 -0.493338 -0.245689 -0.808906 -0.57363 -0.128917 -0.813509 -0.527106 -0.245689 -0.79071 -0.560727 -0.245689 -0.783599 -0.607745 -0.128917 -0.756265 -0.641439 -0.128917 -0.726874 -0.674563 -0.128917 -0.695406 -0.706959 -0.128917 -0.667426 -0.744676 -2.04623e-07 -0.588576 -0.798097 -0.128917 -0.548918 -0.825875 -0.128917 -0.511599 -0.859225 1.91753e-07 -0.418718 -0.898919 -0.128917 -0.371925 -0.919267 -0.128917 -0.323659 -0.93735 -0.128917 -0.274083 -0.953026 -0.128917 -0.223376 -0.96617 -0.128917 -0.119362 -0.984446 -0.128917 -0.16787 -0.954702 -0.245689 -0.116677 -0.962301 -0.245689 -0.0649839 -0.967168 -0.245689 -0.0670387 -0.99775 -2.04623e-07 0.0929705 -0.987288 -0.128917 0.145625 -0.980905 -0.128917 0.197659 -0.971757 -0.128917 0.248859 -0.959922 -0.128917 0.292297 -0.924229 -0.245689 0.340139 -0.907713 -0.245689 0.350894 -0.936415 -2.04623e-07 0.441516 -0.887944 -0.128917 0.485837 -0.86449 -0.128917 0.568993 -0.812174 -0.128917 0.516476 -0.820299 -0.245688 0.556194 -0.793905 -0.245689 0.60766 -0.783665 -0.128917 0.678891 -0.722833 -0.128917 0.629812 -0.736868 -0.245689 0.66362 -0.706573 -0.245689 0.7114 -0.690862 -0.128917 0.741828 -0.658082 -0.128917 0.770187 -0.624653 -0.128917 0.796503 -0.590731 -0.128917 0.820813 -0.556459 -0.128917 0.850258 -0.526366 -2.04623e-07 0.870877 -0.491502 -2.04623e-07 0.906616 -0.421956 -2.04623e-07 0.92188 -0.387476 -2.04623e-07 0.947578 -0.319524 -2.04623e-07 0.958172 -0.286194 1.91753e-07 0.967369 -0.253373 1.91753e-07 0.975249 -0.22111 1.91753e-07 0.981891 -0.189445 1.91753e-07 0.987373 -0.158414 1.91753e-07 0.995152 -0.0983526 1.91753e-07 0.997592 -0.0693609 1.91753e-07 0.999156 -0.0410785 1.91753e-07 0.999909 -0.0135129 1.91753e-07 0.999909 0.0135128 -2.04623e-07 0.964649 0.095338 -0.245689 0.986847 0.0975319 -0.128917 0.967014 0.0672349 -0.245689 0.999156 0.0410787 -2.04623e-07 0.997592 0.0693609 -2.04623e-07 0.995152 0.0983526 -2.04623e-07 0.991769 0.128042 -2.04623e-07 0.987373 0.158414 -2.04623e-07 0.981891 0.189445 -2.04623e-07 0.967111 0.219265 -0.128917 0.959296 0.251259 -0.128917 0.958172 0.286194 -2.04623e-07 0.914187 0.384242 -0.128917 0.906833 0.342478 -0.245689 0.893623 0.375599 -0.245689 0.92188 0.387476 1.91753e-07 0.899051 0.418435 -0.128917 0.882216 0.452852 -0.128917 0.86361 0.4874 -0.128917 0.843163 0.521974 -0.128917 0.820813 0.556459 -0.128917 0.796503 0.590731 -0.128917 0.741828 0.658082 -0.128917 0.752863 0.610602 -0.245689 0.725141 0.643279 -0.245689 0.7114 0.690862 -0.128917 0.644305 0.753825 -0.128917 0.66362 0.706573 -0.245689 0.629812 0.736868 -0.245689 0.60766 0.783664 -0.128917 0.568993 0.812174 -0.128917 0.516476 0.820299 -0.245689 0.474908 0.845044 -0.245689 0.489925 0.871765 -2.04623e-07 0.395515 0.909367 -0.128917 0.347966 0.928601 -0.128917 0.299024 0.945497 -0.128917 0.248859 0.959922 -0.128917 0.197659 0.971757 -0.128917 0.0929707 0.987288 -0.128917 0.14235 0.95884 -0.245688 0.0908794 0.965079 -0.245689 0.0390183 0.968563 -0.245689 0.0402521 0.99919 1.91753e-07 -0.119362 0.984446 -0.128917 -0.171733 0.976672 -0.128917 -0.223376 0.96617 -0.128917 -0.274083 0.953026 -0.128917 -0.316378 0.916265 -0.245689 -0.363559 0.898589 -0.245689 -0.375055 0.927003 -2.04623e-07 -0.463894 0.87646 -0.128917 -0.50733 0.852055 -0.128917 -0.553537 0.832824 -2.04623e-07 -0.626238 0.7689 -0.128917 -0.667426 0.744676 1.91753e-07 -0.756265 0.641438 -0.128917 -0.710524 0.659389 -0.245688 -0.739254 0.62701 -0.245688 -0.808906 0.57363 -0.128917 -0.765972 0.594074 -0.245689 -0.79071 0.560727 -0.245689 -0.815713 0.578457 1.91753e-07 -0.928893 0.370348 -2.04623e-07 -0.906827 0.401305 -0.128917 -0.921142 0.367257 -0.128917 -0.898347 0.439287 1.91753e-07 -0.914457 0.404682 -2.04623e-07 -0.96294 0.269717 -2.04623e-07 -0.933874 0.333556 -0.128917 -0.945101 0.300273 -0.128917 -0.97872 0.205201 -2.04623e-07 -0.976555 0.172398 -0.128917 -0.954588 0.16852 -0.245689 -0.981443 0.14195 -0.128917 -0.989702 0.143144 -2.04623e-07 -0.985291 0.112167 -0.128917 -0.98817 0.0830695 -0.128917 -0.99963 0.027206 1.91753e-07 -0.998479 0.0551305 1.91753e-07 -0.812557 -4.97386e-16 -0.582882 -0.8496 -0.0231227 -0.52692 -0.848642 -1.61832e-16 -0.528968 -0.990147 -0.0546704 -0.128917 -0.98817 -0.0830696 -0.128917 -0.985291 -0.112167 -0.128917 -0.981443 -0.14195 -0.128917 -0.976555 -0.172398 -0.128917 -0.922428 -0.162843 -0.350155 -0.948721 -0.198911 -0.245688 -0.954588 -0.16852 -0.245689 -0.877266 -0.18393 -0.443366 -0.909967 -0.222154 -0.350154 -0.916759 -0.19221 -0.350155 -0.954904 -0.267466 -0.128917 -0.945101 -0.300272 -0.128917 -0.89085 -0.435621 -0.128917 -0.873139 -0.470116 -0.128917 -0.832229 -0.539235 -0.128917 -0.739253 -0.62701 -0.245689 -0.740167 -0.57406 -0.350155 -0.714348 -0.605886 -0.350155 -0.710523 -0.659389 -0.245689 -0.646969 -0.721851 -0.245689 -0.656862 -0.667775 -0.350155 -0.625173 -0.697532 -0.350155 -0.612151 -0.751604 -0.245689 -0.575337 -0.780144 -0.245689 -0.495918 -0.832888 -0.245688 -0.518494 -0.7801 -0.350155 -0.47921 -0.804829 -0.350155 -0.45346 -0.856745 -0.245688 -0.409299 -0.878699 -0.245689 -0.363558 -0.898589 -0.245689 -0.316378 -0.916265 -0.245689 -0.218351 -0.944436 -0.245689 -0.258891 -0.900204 -0.350154 -0.210995 -0.912619 -0.350154 -0.162215 -0.922539 -0.350154 -0.171733 -0.976672 -0.128917 -0.0130109 -0.969261 -0.245689 0.0390185 -0.968563 -0.245689 0.0908792 -0.965079 -0.245689 0.14235 -0.95884 -0.245689 0.193213 -0.949898 -0.245689 0.235066 -0.906717 -0.350155 0.28245 -0.893092 -0.350155 0.299024 -0.945497 -0.128917 0.386618 -0.888911 -0.245689 0.431585 -0.86797 -0.245689 0.474908 -0.845044 -0.245688 0.528361 -0.839175 -0.128917 0.593991 -0.766037 -0.245689 0.644305 -0.753825 -0.128917 0.725141 -0.643279 -0.245689 0.67197 -0.65257 -0.350154 0.700712 -0.621607 -0.350154 0.752863 -0.610602 -0.245689 0.79643 -0.493043 -0.350154 0.824196 -0.510233 -0.245689 0.775318 -0.525617 -0.350154 0.843163 -0.521974 -0.128917 0.844183 -0.476436 -0.245689 0.862371 -0.442666 -0.245689 0.899051 -0.418435 -0.128917 0.887589 -0.299296 -0.350155 0.918534 -0.309731 -0.245689 0.876282 -0.33094 -0.350155 0.939671 -0.316858 -0.128917 0.950176 -0.283806 -0.128917 0.959296 -0.251259 -0.128917 0.967111 -0.219265 -0.128917 0.973698 -0.187865 -0.128917 0.986847 -0.0975318 -0.128917 0.989267 -0.0687821 -0.128917 0.990818 -0.0407357 -0.128917 0.991565 -0.0134002 -0.128917 0.991565 0.0134 -0.128917 0.990818 0.040736 -0.128917 0.989267 0.0687822 -0.128917 0.983493 0.126974 -0.128917 0.979134 0.157092 -0.128917 0.973698 0.187865 -0.128917 0.897512 0.268076 -0.350155 0.928802 0.277422 -0.245689 0.906126 0.237333 -0.350155 0.950176 0.283806 -0.128917 0.939671 0.316858 -0.128917 0.927701 0.350359 -0.128917 0.878828 0.409022 -0.245688 0.862371 0.442666 -0.245688 0.844183 0.476436 -0.245689 0.824196 0.510233 -0.245689 0.802349 0.543942 -0.245689 0.778586 0.577443 -0.245689 0.770187 0.624653 -0.128917 0.695398 0.675322 -0.245689 0.678891 0.722833 -0.128917 0.593991 0.766036 -0.245689 0.537456 0.767159 -0.350155 0.499076 0.792663 -0.350155 0.528361 0.839175 -0.128917 0.431585 0.86797 -0.245689 0.386618 0.888911 -0.245689 0.340139 0.907713 -0.245689 0.292297 0.924229 -0.245689 0.193213 0.949898 -0.245688 0.235065 0.906717 -0.350155 0.186703 0.917896 -0.350155 0.137554 0.926537 -0.350154 0.145625 0.980905 -0.128917 -0.0130107 0.969261 -0.245689 -0.0649835 0.967168 -0.245689 -0.116677 0.962301 -0.245689 -0.16787 0.954702 -0.245689 -0.218351 0.944436 -0.245689 -0.258891 0.900204 -0.350154 -0.305719 0.885397 -0.350154 -0.323658 0.93735 -0.128917 -0.409299 0.878699 -0.245689 -0.45346 0.856745 -0.245689 -0.536571 0.807297 -0.245689 -0.47921 0.804829 -0.350155 -0.518494 0.7801 -0.350155 -0.575337 0.780144 -0.245689 -0.646969 0.721851 -0.245689 -0.591528 0.726283 -0.350155 -0.625173 0.697532 -0.350155 -0.679763 0.691056 -0.245689 -0.726874 0.674562 -0.128917 -0.783599 0.607744 -0.128917 -0.813509 0.527106 -0.245689 -0.890851 0.435621 -0.128917 -0.963362 0.23519 -0.128917 -0.954904 0.267467 -0.128917 -0.933424 0.26145 -0.245689 -0.923842 0.293518 -0.245689 -0.912867 0.326053 -0.245689 -0.970553 0.203488 -0.128917 -0.963128 0.109644 -0.245689 -0.965942 0.0812009 -0.245689 -0.990147 0.0546704 -0.128917 -0.991288 0.0269789 -0.128917 -0.967875 -0.0534406 -0.245689 -0.965942 -0.081201 -0.245689 -0.941692 -0.2299 -0.245688 -0.933424 -0.26145 -0.245689 -0.886428 -0.392278 -0.245689 -0.824744 -0.44406 -0.350154 -0.806308 -0.476718 -0.350154 -0.786102 -0.509348 -0.350154 -0.764072 -0.541836 -0.350154 -0.765972 -0.594074 -0.245689 -0.686586 -0.637174 -0.350155 -0.679763 -0.691056 -0.245689 -0.591528 -0.726283 -0.350155 -0.532004 -0.721386 -0.443366 -0.496158 -0.746494 -0.443366 -0.536571 -0.807297 -0.245689 -0.438183 -0.827882 -0.350154 -0.39551 -0.849096 -0.350154 -0.35131 -0.868316 -0.350154 -0.29255 -0.847255 -0.443366 -0.247739 -0.861424 -0.443366 -0.267917 -0.931589 -0.245689 -0.112746 -0.929882 -0.350154 -0.0627946 -0.934585 -0.350154 -0.0125725 -0.936608 -0.350154 0.037704 -0.935933 -0.350154 0.0878175 -0.932566 -0.350155 0.137554 -0.926537 -0.350155 0.17866 -0.878354 -0.443366 0.224939 -0.867657 -0.443366 0.243261 -0.938329 -0.245689 0.328679 -0.877133 -0.350155 0.373593 -0.858964 -0.350155 0.417045 -0.838728 -0.350155 0.499076 -0.792663 -0.350155 0.43914 -0.781398 -0.443366 0.477576 -0.758516 -0.443366 0.537456 -0.767159 -0.350154 0.582376 -0.681369 -0.443366 0.608594 -0.712043 -0.350154 0.549253 -0.708341 -0.443366 0.641263 -0.682769 -0.350154 0.695398 -0.675322 -0.245689 0.719946 -0.533952 -0.443366 0.752356 -0.557989 -0.350154 0.696159 -0.564614 -0.443366 0.778586 -0.577443 -0.245689 0.802349 -0.543942 -0.245689 0.812637 -0.378216 -0.443366 0.84922 -0.395243 -0.350155 0.79742 -0.409325 -0.443366 0.878827 -0.409023 -0.245689 0.893623 -0.375599 -0.245689 0.906833 -0.342478 -0.245689 0.928802 -0.277422 -0.245689 0.937718 -0.245607 -0.245689 0.945356 -0.214333 -0.245689 0.951795 -0.183639 -0.245688 0.957109 -0.153558 -0.245688 0.96137 -0.124118 -0.245689 0.964649 -0.0953379 -0.245689 0.967014 -0.0672349 -0.245689 0.968531 -0.0398194 -0.245689 0.96926 -0.0130988 -0.245689 0.96926 0.0130986 -0.245689 0.968531 0.0398196 -0.245689 0.96137 0.124118 -0.245689 0.932151 0.0921261 -0.350154 0.928982 0.119936 -0.350154 0.957109 0.153558 -0.245689 0.951795 0.183639 -0.245689 0.945356 0.214333 -0.245689 0.937718 0.245607 -0.245689 0.918534 0.309731 -0.245689 0.876282 0.33094 -0.350155 0.863517 0.362945 -0.350155 0.780602 0.440553 -0.443366 0.815743 0.460386 -0.350154 0.79742 0.409326 -0.443366 0.741919 0.502974 -0.443366 0.775318 0.525617 -0.350154 0.76212 0.471804 -0.443366 0.696159 0.564614 -0.443366 0.727499 0.590031 -0.350154 0.719946 0.533952 -0.443366 0.700711 0.621607 -0.350154 0.641263 0.682769 -0.350154 0.643022 0.624459 -0.443366 0.613638 0.653356 -0.443366 0.608594 0.712043 -0.350154 0.57398 0.740229 -0.350154 0.556194 0.793905 -0.245689 0.458909 0.816575 -0.350155 0.417045 0.838728 -0.350155 0.373593 0.858964 -0.350155 0.28245 0.893092 -0.350155 0.314521 0.839347 -0.443366 0.270282 0.854619 -0.443366 0.224939 0.867657 -0.443366 0.243261 0.938329 -0.245689 0.0878177 0.932566 -0.350154 0.0377038 0.935933 -0.350154 -0.0125724 0.936608 -0.350154 -0.0627943 0.934585 -0.350154 -0.112746 0.929882 -0.350154 -0.162215 0.922539 -0.350154 -0.201906 0.873304 -0.443366 -0.247739 0.861424 -0.443366 -0.267917 0.931589 -0.245689 -0.351311 0.868316 -0.350154 -0.39551 0.849096 -0.350154 -0.458567 0.770158 -0.443366 -0.419306 0.792217 -0.443366 -0.495917 0.832888 -0.245689 -0.555954 0.753861 -0.350155 -0.612151 0.751604 -0.245689 -0.656862 0.667775 -0.350155 -0.686586 0.637174 -0.350155 -0.714348 0.605886 -0.350155 -0.740167 0.57406 -0.350154 -0.764072 0.541836 -0.350154 -0.771573 0.456182 -0.443366 -0.886428 0.392278 -0.245689 -0.900422 0.358996 -0.245689 -0.806307 0.476718 -0.350154 -0.916759 0.19221 -0.350155 -0.922428 0.162843 -0.350155 -0.941692 0.2299 -0.245689 -0.882113 0.315069 -0.350154 -0.892718 0.28363 -0.350154 -0.948721 0.198911 -0.245689 -0.959366 0.138757 -0.245689 -0.930681 0.10595 -0.350155 -0.9334 0.0784653 -0.350155 -0.96899 0.0263721 -0.245689 -0.967875 0.0534407 -0.245689 -0.686794 -8.25697e-17 -0.726852 -0.740552 -0.0201548 -0.671697 -0.732029 -0 -0.681273 -0.935267 -0.0516403 -0.350155 -0.797813 -0.0217132 -0.602514 -0.773786 -1.65973e-16 -0.633447 -0.844461 -0.0961348 -0.52692 -0.890588 -0.101386 -0.443366 -0.846928 -0.0711962 -0.52692 -0.841163 -0.12166 -0.52692 -0.88711 -0.128306 -0.443366 -0.863122 -0.241758 -0.443366 -0.870766 -0.212584 -0.443366 -0.825666 -0.201574 -0.52692 -0.819665 -0.362733 -0.443366 -0.805225 -0.393751 -0.443366 -0.713276 -0.462161 -0.52692 -0.752238 -0.487406 -0.443366 -0.73161 -0.432554 -0.52692 -0.731156 -0.518495 -0.443366 -0.708282 -0.54933 -0.443366 -0.683575 -0.579786 -0.443366 -0.596009 -0.605911 -0.52692 -0.628566 -0.639008 -0.443366 -0.622979 -0.578146 -0.52692 -0.598241 -0.667483 -0.443366 -0.536728 -0.658999 -0.52692 -0.504449 -0.684022 -0.52692 -0.555954 -0.753861 -0.350155 -0.458567 -0.770158 -0.443366 -0.419306 -0.792217 -0.443366 -0.378472 -0.812518 -0.443366 -0.277397 -0.803372 -0.526919 -0.318764 -0.787874 -0.52692 -0.30572 -0.885397 -0.350154 -0.201906 -0.873304 -0.443366 -0.155227 -0.882797 -0.443366 -0.107889 -0.889824 -0.443366 -0.0600895 -0.894324 -0.443366 -0.0120309 -0.89626 -0.443366 0.0360798 -0.895614 -0.443366 0.0840345 -0.892393 -0.443366 0.124811 -0.840701 -0.52692 0.169407 -0.832861 -0.52692 0.186703 -0.917896 -0.350155 0.270282 -0.854619 -0.443366 0.31452 -0.839347 -0.443366 0.357499 -0.821961 -0.443366 0.416395 -0.740926 -0.52692 0.378409 -0.761027 -0.52692 0.458909 -0.816575 -0.350155 0.514303 -0.734111 -0.443366 0.57398 -0.740229 -0.350154 0.613638 -0.653356 -0.443366 0.643022 -0.624458 -0.443366 0.670526 -0.594829 -0.443366 0.727499 -0.590031 -0.350154 0.741919 -0.502974 -0.443366 0.76212 -0.471804 -0.443366 0.815743 -0.460386 -0.350155 0.833318 -0.427752 -0.350155 0.863517 -0.362945 -0.350155 0.814364 -0.243241 -0.52692 0.858848 -0.256527 -0.443366 0.805361 -0.271569 -0.52692 0.897512 -0.268076 -0.350155 0.906126 -0.237333 -0.350155 0.913508 -0.207112 -0.350155 0.91973 -0.177452 -0.350155 0.924864 -0.148385 -0.350154 0.928982 -0.119936 -0.350154 0.932151 -0.0921261 -0.350154 0.934436 -0.0649698 -0.350154 0.935901 -0.0384779 -0.350154 0.936606 -0.0126575 -0.350154 0.936606 0.0126573 -0.350154 0.935901 0.0384781 -0.350154 0.934436 0.0649698 -0.350154 0.834524 0.161013 -0.52692 0.78803 0.126431 -0.602514 0.783656 0.151198 -0.602514 0.924864 0.148385 -0.350155 0.91973 0.177452 -0.350155 0.913508 0.207112 -0.350155 0.805361 0.271569 -0.52692 0.849352 0.286403 -0.443366 0.814364 0.243241 -0.52692 0.887589 0.299296 -0.350155 0.770547 0.358627 -0.52692 0.812637 0.378216 -0.443366 0.78352 0.329321 -0.52692 0.84922 0.395243 -0.350155 0.833318 0.427753 -0.350154 0.79643 0.493043 -0.350154 0.752356 0.557989 -0.350154 0.670526 0.594829 -0.443366 0.67197 0.65257 -0.350154 0.582376 0.681369 -0.443366 0.487665 0.696088 -0.52692 0.514304 0.73411 -0.443366 0.520805 0.671653 -0.52692 0.477576 0.758516 -0.443366 0.439139 0.781398 -0.443366 0.399079 0.802597 -0.443366 0.338983 0.779388 -0.52692 0.29823 0.795873 -0.52692 0.32868 0.877132 -0.350155 0.17866 0.878355 -0.443366 0.131628 0.886623 -0.443366 0.0840346 0.892393 -0.443366 0.0360796 0.895614 -0.443366 -0.0120308 0.89626 -0.443366 -0.0600892 0.894324 -0.443366 -0.102301 0.843736 -0.52692 -0.147187 0.837073 -0.52692 -0.155227 0.882797 -0.443366 -0.191448 0.828072 -0.52692 -0.210995 0.912619 -0.350154 -0.292549 0.847255 -0.443366 -0.336177 0.83091 -0.443366 -0.378472 0.812518 -0.443366 -0.438183 0.827881 -0.350155 -0.496158 0.746494 -0.443366 -0.536728 0.658998 -0.52692 -0.566046 0.694995 -0.443366 -0.504449 0.684022 -0.52692 -0.598241 0.667483 -0.443366 -0.62298 0.578145 -0.52692 -0.657009 0.609726 -0.443366 -0.596009 0.605911 -0.52692 -0.671597 0.520878 -0.52692 -0.708282 0.54933 -0.443366 -0.64817 0.549756 -0.52692 -0.713276 0.462161 -0.526919 -0.752238 0.487406 -0.443366 -0.693287 0.491639 -0.52692 -0.786102 0.509348 -0.350154 -0.870087 0.346902 -0.350154 -0.901978 0.252642 -0.350155 -0.909967 0.222154 -0.350155 -0.854261 0.271411 -0.443366 -0.844113 0.301496 -0.443366 -0.927046 0.134082 -0.350155 -0.882691 0.155828 -0.443366 -0.890588 0.101386 -0.443366 -0.89319 0.0750851 -0.443366 -0.936345 0.0254836 -0.350155 -0.935267 0.0516403 -0.350155 -0.882128 -1.77917e-16 -0.47101 -0.894977 -0.0494157 -0.443366 -0.89319 -0.0750852 -0.443366 -0.882691 -0.155828 -0.443366 -0.785955 -0.13875 -0.602514 -0.831829 -0.174403 -0.52692 -0.836973 -0.147757 -0.52692 -0.76853 -0.215263 -0.602514 -0.702723 -0.378361 -0.602514 -0.748338 -0.402921 -0.52692 -0.716978 -0.350598 -0.602514 -0.789215 -0.42493 -0.443366 -0.771573 -0.456181 -0.443366 -0.630659 -0.489128 -0.602514 -0.671597 -0.520878 -0.52692 -0.651027 -0.461671 -0.602514 -0.64817 -0.549756 -0.52692 -0.657009 -0.609726 -0.443366 -0.567256 -0.632911 -0.52692 -0.566046 -0.694995 -0.443366 -0.47046 -0.70783 -0.52692 -0.434815 -0.730268 -0.52692 -0.397589 -0.751185 -0.52692 -0.336994 -0.723472 -0.602514 -0.299334 -0.739849 -0.602514 -0.336176 -0.83091 -0.443366 -0.234907 -0.816808 -0.526919 -0.191448 -0.828072 -0.52692 -0.147187 -0.837073 -0.52692 -0.102301 -0.843736 -0.52692 -0.0569772 -0.848003 -0.52692 -0.0114078 -0.849838 -0.52692 0.0321257 -0.797462 -0.602514 0.0748249 -0.794593 -0.602514 0.079682 -0.846172 -0.52692 0.117203 -0.789456 -0.602514 0.131628 -0.886623 -0.443366 0.213289 -0.822717 -0.52692 0.256283 -0.810355 -0.52692 0.29823 -0.795873 -0.52692 0.31832 -0.731881 -0.602514 0.355343 -0.714638 -0.602514 0.399079 -0.802597 -0.443366 0.45284 -0.71923 -0.52692 0.45794 -0.653657 -0.602514 0.489059 -0.630712 -0.602514 0.520805 -0.671653 -0.52692 0.552212 -0.646078 -0.526919 0.546388 -0.581753 -0.602514 0.572552 -0.556023 -0.602514 0.609718 -0.592115 -0.526919 0.635796 -0.56402 -0.52692 0.660102 -0.53537 -0.52692 0.682657 -0.506296 -0.52692 0.695054 -0.392272 -0.602514 0.740171 -0.417735 -0.52692 0.678598 -0.420097 -0.602514 0.780602 -0.440553 -0.443366 0.756118 -0.388125 -0.52692 0.770547 -0.358627 -0.52692 0.826318 -0.34731 -0.443366 0.838533 -0.316683 -0.443366 0.849353 -0.286403 -0.443366 0.867092 -0.227109 -0.443366 0.874155 -0.19819 -0.443366 0.880109 -0.169808 -0.443366 0.885022 -0.141993 -0.443366 0.888962 -0.11477 -0.443366 0.891995 -0.0881574 -0.443366 0.894182 -0.062171 -0.443366 0.895584 -0.0368203 -0.443366 0.896259 -0.0121122 -0.443366 0.896259 0.012112 -0.443366 0.895584 0.0368205 -0.443366 0.894182 0.062171 -0.443366 0.891995 0.0881574 -0.443366 0.888962 0.114769 -0.443366 0.885022 0.141993 -0.443366 0.880109 0.169808 -0.443366 0.874155 0.19819 -0.443366 0.867092 0.227109 -0.443366 0.858848 0.256527 -0.443366 0.838533 0.316683 -0.443366 0.826318 0.34731 -0.443366 0.756118 0.388125 -0.52692 0.740171 0.417735 -0.52692 0.722647 0.447367 -0.526919 0.703492 0.476923 -0.526919 0.682657 0.506296 -0.526919 0.660102 0.53537 -0.52692 0.597041 0.52964 -0.602514 0.572552 0.556023 -0.602514 0.609717 0.592115 -0.52692 0.581855 0.619516 -0.52692 0.518552 0.606696 -0.602514 0.489059 0.630712 -0.602514 0.549253 0.708341 -0.443366 0.452841 0.719229 -0.52692 0.416394 0.740926 -0.52692 0.355343 0.714638 -0.602514 0.31832 0.731881 -0.602514 0.357499 0.821961 -0.443366 0.256283 0.810355 -0.52692 0.213288 0.822717 -0.52692 0.169407 0.832861 -0.52692 0.124811 0.840701 -0.52692 0.0796821 0.846172 -0.52692 0.0342109 0.849226 -0.52692 -0.0107123 0.798036 -0.602514 -0.0535039 0.796313 -0.602514 -0.0569769 0.848003 -0.526919 -0.0960653 0.792306 -0.602514 -0.107889 0.889824 -0.443366 -0.234907 0.816807 -0.52692 -0.277397 0.803372 -0.52692 -0.318765 0.787874 -0.52692 -0.336994 0.723472 -0.602514 -0.373354 0.705396 -0.602514 -0.397589 0.751185 -0.52692 -0.434815 0.730268 -0.52692 -0.47046 0.70783 -0.52692 -0.532004 0.721386 -0.443366 -0.567256 0.632911 -0.52692 -0.628566 0.639008 -0.443366 -0.683575 0.579785 -0.443366 -0.731156 0.518495 -0.443366 -0.73161 0.432554 -0.526919 -0.748338 0.402921 -0.52692 -0.763519 0.373356 -0.52692 -0.863122 0.241758 -0.443366 -0.870766 0.212584 -0.443366 -0.810015 0.257354 -0.52692 -0.800393 0.28588 -0.52692 -0.877266 0.18393 -0.443366 -0.88711 0.128306 -0.443366 -0.836973 0.147757 -0.52692 -0.844461 0.0961347 -0.52692 -0.846928 0.0711962 -0.52692 -0.896009 0.0243858 -0.443366 -0.894977 0.0494157 -0.443366 -0.848623 -0.0468562 -0.52692 -0.60592 -0.0164907 -0.795355 -0.677048 -0.0184265 -0.735709 -0.637357 1.28778e-16 -0.770569 -0.736072 -0.0837956 -0.671697 -0.674918 -0.0567363 -0.735709 -0.672952 -0.0766099 -0.735709 -0.662885 -0.138982 -0.735709 -0.719689 -0.175701 -0.671697 -0.725061 -0.152018 -0.671697 -0.818417 -0.229236 -0.52692 -0.741357 -0.295577 -0.602514 -0.777211 -0.343945 -0.52692 -0.763519 -0.373357 -0.52692 -0.687014 -0.406187 -0.602514 -0.669798 -0.43399 -0.602514 -0.693287 -0.491639 -0.52692 -0.564975 -0.479193 -0.671697 -0.543018 -0.503939 -0.671697 -0.585006 -0.542904 -0.602514 -0.55968 -0.568978 -0.602514 -0.494447 -0.551675 -0.671697 -0.467837 -0.574414 -0.671697 -0.504011 -0.618829 -0.602514 -0.4737 -0.642327 -0.602514 -0.441783 -0.664684 -0.602514 -0.408311 -0.685754 -0.602514 -0.346557 -0.654768 -0.671697 -0.312807 -0.671546 -0.671697 -0.358869 -0.770434 -0.52692 -0.260488 -0.754402 -0.602514 -0.220588 -0.767019 -0.602514 -0.179778 -0.777597 -0.602514 -0.138215 -0.786049 -0.602514 -0.0960654 -0.792306 -0.602514 -0.049664 -0.739159 -0.671697 -0.00994356 -0.740759 -0.671697 -0.0107124 -0.798036 -0.602514 0.02982 -0.740226 -0.671697 0.0342111 -0.849226 -0.52692 0.159081 -0.782093 -0.602514 0.200288 -0.772568 -0.602514 0.240661 -0.760959 -0.602514 0.280051 -0.747361 -0.602514 0.338983 -0.779388 -0.52692 0.391013 -0.695762 -0.602514 0.425237 -0.675389 -0.602514 0.487665 -0.696088 -0.52692 0.518552 -0.606696 -0.602514 0.581855 -0.619516 -0.526919 0.55419 -0.491626 -0.671697 0.575376 -0.466653 -0.671697 0.619865 -0.502736 -0.602514 0.595036 -0.441311 -0.671697 0.613196 -0.415709 -0.671697 0.66061 -0.447852 -0.602514 0.703491 -0.476923 -0.52692 0.722647 -0.447367 -0.52692 0.682953 -0.287052 -0.671697 0.73576 -0.309248 -0.602514 0.671645 -0.312596 -0.671697 0.78352 -0.329322 -0.52692 0.795102 -0.300281 -0.52692 0.716652 -0.187705 -0.671697 0.772065 -0.202219 -0.602514 0.709838 -0.21202 -0.671697 0.822181 -0.215346 -0.52692 0.828879 -0.187925 -0.52692 0.834524 -0.161013 -0.52692 0.839183 -0.134638 -0.52692 0.842919 -0.108825 -0.52692 0.845795 -0.0835913 -0.526919 0.847868 -0.0589509 -0.526919 0.849198 -0.0349133 -0.526919 0.849837 -0.0114849 -0.52692 0.849837 0.0114847 -0.52692 0.849198 0.0349134 -0.52692 0.847868 0.0589509 -0.52692 0.845794 0.0835913 -0.52692 0.842919 0.108825 -0.52692 0.839183 0.134638 -0.52692 0.828879 0.187925 -0.52692 0.822181 0.215346 -0.52692 0.764725 0.228414 -0.602514 0.75627 0.255015 -0.602514 0.795102 0.300281 -0.52692 0.73576 0.309247 -0.602514 0.723578 0.336766 -0.602514 0.645168 0.364117 -0.671697 0.629893 0.389946 -0.671697 0.678598 0.420097 -0.602514 0.613196 0.415708 -0.671697 0.595036 0.441311 -0.671697 0.641045 0.475435 -0.602514 0.619866 0.502736 -0.602514 0.635796 0.56402 -0.52692 0.546388 0.581753 -0.602514 0.552212 0.646078 -0.52692 0.45794 0.653657 -0.602514 0.425238 0.675389 -0.602514 0.362949 0.645826 -0.671697 0.329839 0.663347 -0.671697 0.378409 0.761027 -0.52692 0.280052 0.747361 -0.602514 0.240661 0.760959 -0.602514 0.200287 0.772568 -0.602514 0.159081 0.782093 -0.602514 0.117203 0.789456 -0.602514 0.0694547 0.737563 -0.671697 0.0298198 0.740226 -0.671697 0.0321255 0.797461 -0.602514 -0.00994344 0.740759 -0.671697 -0.0114076 0.849839 -0.526919 -0.138215 0.786049 -0.602514 -0.179778 0.777597 -0.602514 -0.220588 0.767019 -0.602514 -0.260488 0.754402 -0.602514 -0.27785 0.686748 -0.671697 -0.312807 0.671546 -0.671697 -0.358869 0.770434 -0.52692 -0.408311 0.685754 -0.602514 -0.410075 0.616978 -0.671697 -0.439702 0.596226 -0.671697 -0.4737 0.642328 -0.602514 -0.504011 0.618829 -0.602514 -0.494447 0.551675 -0.671697 -0.51951 0.528141 -0.671697 -0.559679 0.568978 -0.602514 -0.585006 0.542904 -0.602514 -0.608661 0.516245 -0.602514 -0.630659 0.489127 -0.602514 -0.651027 0.461671 -0.602514 -0.669798 0.43399 -0.602514 -0.652287 0.351205 -0.671697 -0.665519 0.325435 -0.671697 -0.687014 0.406188 -0.602514 -0.818417 0.229237 -0.52692 -0.825666 0.201574 -0.52692 -0.751604 0.268454 -0.602514 -0.760641 0.241667 -0.602514 -0.831829 0.174403 -0.52692 -0.841163 0.12166 -0.52692 -0.795303 0.0668564 -0.602514 -0.848623 0.0468562 -0.52692 -0.792986 0.0902747 -0.602514 -0.8496 0.0231228 -0.52692 -0.452944 2.51061e-17 -0.891539 -0.525217 -0.0142943 -0.850848 -0.5218 -8.88038e-17 -0.853068 -0.796895 -0.0440001 -0.602514 -0.795303 -0.0668564 -0.602514 -0.792986 -0.0902749 -0.602514 -0.789889 -0.114244 -0.602514 -0.602254 -0.0685616 -0.795355 -0.599902 -0.0867659 -0.795355 -0.670323 -0.0969512 -0.735709 -0.781124 -0.163772 -0.602514 -0.775337 -0.189287 -0.602514 -0.629138 -0.250836 -0.735709 -0.61936 -0.27409 -0.735709 -0.677454 -0.299799 -0.671697 -0.729836 -0.32298 -0.602514 -0.665519 -0.325435 -0.671697 -0.652287 -0.351205 -0.671697 -0.637705 -0.377034 -0.671697 -0.621725 -0.402841 -0.671697 -0.604301 -0.428536 -0.671697 -0.585395 -0.454022 -0.671697 -0.60866 -0.516245 -0.602514 -0.51951 -0.528141 -0.671697 -0.532678 -0.594332 -0.602514 -0.439702 -0.596226 -0.671697 -0.410075 -0.616978 -0.671697 -0.346505 -0.581951 -0.735709 -0.316839 -0.59862 -0.735709 -0.373353 -0.705396 -0.602514 -0.27785 -0.686748 -0.671697 -0.241792 -0.700257 -0.671697 -0.204756 -0.711968 -0.671697 -0.166875 -0.721786 -0.671697 -0.117293 -0.667065 -0.735708 -0.0815239 -0.672374 -0.735708 -0.0891705 -0.73544 -0.671697 -0.0454052 -0.675775 -0.735708 -0.0535041 -0.796313 -0.602514 0.0694545 -0.737563 -0.671697 0.108791 -0.732794 -0.671697 0.147663 -0.725961 -0.671697 0.185912 -0.717119 -0.671697 0.204232 -0.645772 -0.735709 0.23766 -0.634232 -0.735709 0.259951 -0.693721 -0.671697 0.270136 -0.621095 -0.735709 0.295473 -0.679352 -0.671697 0.329839 -0.663347 -0.671697 0.362949 -0.645826 -0.671697 0.360869 -0.573155 -0.735709 0.388621 -0.554713 -0.735709 0.425072 -0.606743 -0.671697 0.453958 -0.585444 -0.671697 0.481334 -0.563152 -0.671697 0.507172 -0.539999 -0.671697 0.531458 -0.516115 -0.671697 0.597041 -0.52964 -0.602514 0.641045 -0.475435 -0.602514 0.629893 -0.389946 -0.671697 0.645168 -0.364117 -0.671697 0.710029 -0.364466 -0.602514 0.723578 -0.336767 -0.602514 0.746636 -0.281977 -0.602514 0.75627 -0.255015 -0.602514 0.764725 -0.228414 -0.602514 0.778354 -0.17647 -0.602514 0.783655 -0.151198 -0.602514 0.78803 -0.126431 -0.602514 0.791539 -0.102192 -0.602514 0.794239 -0.078496 -0.602514 0.796186 -0.0553575 -0.602514 0.797435 -0.0327851 -0.602514 0.798035 -0.0107848 -0.602514 0.798035 0.0107846 -0.602514 0.797435 0.0327853 -0.602514 0.796186 0.0553575 -0.602514 0.794239 0.078496 -0.602514 0.791539 0.102192 -0.602514 0.660534 0.149757 -0.735709 0.591141 0.134024 -0.795355 0.655197 0.171609 -0.735709 0.778354 0.17647 -0.602514 0.772065 0.202219 -0.602514 0.641793 0.216413 -0.735709 0.633618 0.239294 -0.735709 0.693048 0.261739 -0.671697 0.746636 0.281977 -0.602514 0.61405 0.28579 -0.735709 0.602551 0.309297 -0.735709 0.659068 0.338308 -0.671697 0.710029 0.364467 -0.602514 0.695054 0.392271 -0.602514 0.66061 0.447852 -0.602514 0.526036 0.426637 -0.735709 0.506667 0.449468 -0.735708 0.55419 0.491627 -0.671697 0.531458 0.516115 -0.671697 0.463681 0.493693 -0.735708 0.440059 0.514861 -0.735709 0.481334 0.563152 -0.671697 0.453958 0.585444 -0.671697 0.425072 0.606743 -0.671697 0.360869 0.573155 -0.735709 0.331825 0.590445 -0.735709 0.391013 0.695763 -0.602514 0.295473 0.679352 -0.671697 0.259952 0.693721 -0.671697 0.223388 0.706343 -0.671697 0.185912 0.717119 -0.671697 0.135001 0.663708 -0.735709 0.0994617 0.669955 -0.735709 0.108791 0.732794 -0.671697 0.0634987 0.674315 -0.735709 0.074825 0.794593 -0.602514 -0.0496637 0.739159 -0.671697 -0.0891704 0.73544 -0.671697 -0.128295 0.729632 -0.671697 -0.166875 0.721786 -0.671697 -0.204756 0.711968 -0.671697 -0.221058 0.640208 -0.735709 -0.254024 0.627857 -0.735709 -0.299334 0.739849 -0.602514 -0.346557 0.654768 -0.671697 -0.379006 0.636536 -0.671697 -0.441783 0.664684 -0.602514 -0.467837 0.574414 -0.671697 -0.532678 0.594332 -0.602514 -0.543018 0.503939 -0.671697 -0.564975 0.479193 -0.671697 -0.585395 0.454022 -0.671697 -0.604301 0.428536 -0.671697 -0.621725 0.402841 -0.671697 -0.702723 0.378361 -0.602514 -0.645502 0.205085 -0.735709 -0.652197 0.182679 -0.735709 -0.637705 0.377034 -0.671697 -0.76853 0.215264 -0.602514 -0.775337 0.189287 -0.602514 -0.706047 0.224322 -0.671697 -0.69766 0.249187 -0.671697 -0.785955 0.13875 -0.602514 -0.781125 0.163772 -0.602514 -0.789889 0.114245 -0.602514 -0.729545 0.128792 -0.671697 -0.736072 0.0837955 -0.671697 -0.738222 0.0620579 -0.671697 -0.796894 0.0440001 -0.602514 -0.797813 0.0217133 -0.602514 -0.739699 -0.0408421 -0.671697 -0.738222 -0.062058 -0.671697 -0.733197 -0.106045 -0.671697 -0.729545 -0.128792 -0.671697 -0.69766 -0.249186 -0.671697 -0.688148 -0.274363 -0.671697 -0.583021 -0.344703 -0.735708 -0.596352 -0.321088 -0.735708 -0.533702 -0.287356 -0.795355 -0.552481 -0.391788 -0.735709 -0.568411 -0.368297 -0.735709 -0.508696 -0.329605 -0.795355 -0.535196 -0.415088 -0.735709 -0.516527 -0.438101 -0.735709 -0.496453 -0.460725 -0.735709 -0.452047 -0.504368 -0.735709 -0.474961 -0.482851 -0.735709 -0.425063 -0.432125 -0.795355 -0.427719 -0.525157 -0.735709 -0.401996 -0.545098 -0.735709 -0.37491 -0.56407 -0.735709 -0.335524 -0.504812 -0.795355 -0.379006 -0.636536 -0.671697 -0.285983 -0.61396 -0.735709 -0.254024 -0.627857 -0.735709 -0.221058 -0.640208 -0.735709 -0.152565 -0.659891 -0.735709 -0.187198 -0.650915 -0.735709 -0.167532 -0.582532 -0.795355 -0.136537 -0.590566 -0.795355 -0.128295 -0.729632 -0.671697 -0.00909088 -0.677237 -0.735709 0.0272628 -0.676749 -0.735709 0.0634986 -0.674315 -0.735709 0.0994617 -0.669955 -0.735709 0.135001 -0.663708 -0.735709 0.16997 -0.655624 -0.735709 0.152114 -0.586747 -0.795355 0.223389 -0.706343 -0.671697 0.301555 -0.606463 -0.735709 0.331825 -0.590445 -0.735709 0.394717 -0.626914 -0.671697 0.41503 -0.535241 -0.735709 0.463681 -0.493693 -0.735709 0.440059 -0.51486 -0.735709 0.393828 -0.460772 -0.795355 0.485884 -0.471857 -0.735709 0.506667 -0.449468 -0.735709 0.526036 -0.426637 -0.735708 0.54401 -0.403468 -0.735708 0.560613 -0.38006 -0.735709 0.575878 -0.356507 -0.735709 0.589843 -0.332893 -0.735709 0.659068 -0.338308 -0.671697 0.61405 -0.28579 -0.735709 0.624388 -0.262437 -0.735709 0.693048 -0.261739 -0.671697 0.70199 -0.236712 -0.671697 0.595168 -0.114831 -0.795355 0.515897 -0.0995369 -0.850848 0.59849 -0.0960216 -0.795355 0.72249 -0.163804 -0.671697 0.72741 -0.140346 -0.671697 0.731471 -0.117357 -0.671697 0.734728 -0.0948571 -0.671697 0.737234 -0.0728621 -0.671697 0.739042 -0.0513844 -0.671697 0.740201 -0.030432 -0.671697 0.740758 -0.0100107 -0.671697 0.740758 0.0100106 -0.671697 0.740201 0.0304322 -0.671697 0.739042 0.0513844 -0.671697 0.737234 0.0728621 -0.671697 0.734728 0.094857 -0.671697 0.731471 0.117357 -0.671697 0.72741 0.140346 -0.671697 0.72249 0.163804 -0.671697 0.716652 0.187705 -0.671697 0.709838 0.21202 -0.671697 0.70199 0.236712 -0.671697 0.682953 0.287052 -0.671697 0.671645 0.312596 -0.671697 0.589843 0.332893 -0.735709 0.575878 0.356507 -0.735709 0.560613 0.38006 -0.735709 0.54401 0.403468 -0.735709 0.575376 0.466653 -0.671697 0.485885 0.471857 -0.735708 0.507172 0.539999 -0.671697 0.41503 0.535241 -0.735709 0.388621 0.554713 -0.735709 0.347794 0.496437 -0.795355 0.394717 0.626914 -0.671697 0.301555 0.606463 -0.735709 0.270136 0.621095 -0.735709 0.23766 0.634232 -0.735709 0.204232 0.645772 -0.735709 0.16997 0.655624 -0.735709 0.152114 0.586747 -0.795355 0.147663 0.725961 -0.671697 0.0272627 0.676749 -0.735709 -0.00909076 0.677237 -0.735709 -0.0454049 0.675775 -0.735709 -0.0815238 0.672374 -0.735709 -0.117294 0.667065 -0.735708 -0.152565 0.659892 -0.735708 -0.187198 0.650915 -0.735708 -0.167532 0.582532 -0.795355 -0.241792 0.700257 -0.671697 -0.285983 0.61396 -0.735709 -0.316839 0.59862 -0.735709 -0.37491 0.56407 -0.735709 -0.346505 0.581951 -0.735709 -0.310103 0.520814 -0.795355 -0.401996 0.545098 -0.735709 -0.427719 0.525157 -0.735709 -0.452047 0.504368 -0.735709 -0.474961 0.482851 -0.735709 -0.516527 0.438101 -0.735709 -0.496453 0.460725 -0.735709 -0.444298 0.412323 -0.795355 -0.552481 0.391788 -0.735709 -0.535196 0.415088 -0.735709 -0.478971 0.371481 -0.795355 -0.583021 0.344703 -0.735709 -0.568411 0.368297 -0.735709 -0.508696 0.329605 -0.795355 -0.608449 0.297528 -0.735709 -0.713371 0.199814 -0.671697 -0.719689 0.175701 -0.671697 -0.725061 0.152018 -0.671697 -0.733197 0.106045 -0.671697 -0.666985 0.117747 -0.735709 -0.672952 0.0766098 -0.735709 -0.674918 0.0567363 -0.735708 -0.740552 0.0201549 -0.671697 -0.739699 0.0408421 -0.671697 -0.0625688 -4.981e-17 -0.998041 -0.056897 -0.00154851 -0.998379 -0.180587 -5.50038e-17 -0.983559 -0.676268 -0.0373398 -0.735709 -0.324982 -0.00884469 -0.945679 -0.28421 -1.14944e-16 -0.958762 -0.200187 -0.00544828 -0.979743 -0.666985 -0.117747 -0.735709 -0.517411 -0.0913421 -0.850848 -0.426059 -0.0752151 -0.901563 -0.514231 -0.107815 -0.850848 -0.637834 -0.227818 -0.735709 -0.480467 -0.212625 -0.850848 -0.544528 -0.266271 -0.795355 -0.554293 -0.245296 -0.795355 -0.608449 -0.297528 -0.735708 -0.415176 -0.322003 -0.850848 -0.462263 -0.392076 -0.795355 -0.478971 -0.371481 -0.795355 -0.404557 -0.451381 -0.795355 -0.311847 -0.422858 -0.850848 -0.359764 -0.487833 -0.795355 -0.310103 -0.520814 -0.795355 -0.283553 -0.535732 -0.795355 -0.197058 -0.487058 -0.850848 -0.197835 -0.57295 -0.795355 -0.227337 -0.561897 -0.795355 -0.171485 -0.496639 -0.850848 -0.104971 -0.596986 -0.795355 -0.0729594 -0.601737 -0.795355 -0.0406351 -0.604781 -0.795355 -0.00813583 -0.60609 -0.795355 0.0243987 -0.605653 -0.795355 0.0568277 -0.603474 -0.795355 0.104726 -0.514869 -0.850848 0.120818 -0.593981 -0.795355 0.182777 -0.57793 -0.795355 0.212692 -0.567603 -0.795355 0.241756 -0.555846 -0.795355 0.257412 -0.458035 -0.850848 0.322958 -0.512942 -0.795355 0.296965 -0.528415 -0.795355 0.347794 -0.496437 -0.795355 0.376923 -0.366042 -0.850848 0.453439 -0.402249 -0.795355 0.43484 -0.422286 -0.795355 0.486859 -0.361081 -0.795355 0.53925 -0.276804 -0.795355 0.527877 -0.297921 -0.795355 0.457569 -0.258241 -0.850848 0.602551 -0.309297 -0.735709 0.497868 -0.167882 -0.850848 0.491526 -0.185631 -0.850848 0.404744 -0.152857 -0.901563 0.633618 -0.239294 -0.735709 0.641793 -0.216413 -0.735709 0.648968 -0.193839 -0.735709 0.655197 -0.171609 -0.735709 0.660534 -0.149757 -0.735709 0.665033 -0.128311 -0.735709 0.668746 -0.107293 -0.735709 0.671723 -0.0867229 -0.735709 0.674014 -0.066614 -0.735709 0.675667 -0.046978 -0.735709 0.676727 -0.0278224 -0.735709 0.677236 -0.0091523 -0.735709 0.677237 0.00915217 -0.735708 0.676727 0.0278226 -0.735708 0.675667 0.0469781 -0.735708 0.674014 0.066614 -0.735709 0.671723 0.0867228 -0.735709 0.668746 0.107293 -0.735709 0.665033 0.128311 -0.735709 0.648968 0.193839 -0.735709 0.491527 0.185632 -0.850848 0.558792 0.234866 -0.795355 0.567053 0.214155 -0.795355 0.624388 0.262437 -0.735709 0.54954 0.255766 -0.795355 0.527877 0.297921 -0.795355 0.501718 0.340133 -0.795355 0.470773 0.381816 -0.795355 0.376923 0.366042 -0.850848 0.414969 0.441828 -0.795355 0.43484 0.422286 -0.795355 0.393828 0.460772 -0.795355 0.322958 0.512942 -0.795355 0.296965 0.528415 -0.795355 0.269875 0.542751 -0.795355 0.184364 0.492003 -0.850848 0.182777 0.577931 -0.795355 0.212693 0.567603 -0.795355 0.158432 0.500955 -0.850848 0.120818 0.593981 -0.795355 0.0890127 0.599573 -0.795355 0.0568278 0.603474 -0.795355 0.0243986 0.605653 -0.795355 -0.00813573 0.60609 -0.795355 -0.0406349 0.604781 -0.795355 -0.0909901 0.517473 -0.850848 -0.136537 0.590566 -0.795355 -0.104971 0.596986 -0.795355 -0.118352 0.511908 -0.850848 -0.197835 0.57295 -0.795355 -0.227337 0.561897 -0.795355 -0.245787 0.464377 -0.850848 -0.283553 0.535732 -0.795355 -0.335523 0.504812 -0.795355 -0.331801 0.407388 -0.850848 -0.404557 0.451381 -0.795355 -0.382785 0.469986 -0.795355 -0.472002 0.230806 -0.850848 -0.554293 0.245296 -0.795355 -0.544528 0.266271 -0.795355 -0.61936 0.27409 -0.735709 -0.657974 0.160634 -0.735709 -0.670323 0.0969513 -0.735709 -0.596914 0.105377 -0.795355 -0.662885 0.138982 -0.735709 -0.602254 0.0685615 -0.795355 -0.604014 0.0507758 -0.795355 -0.677048 0.0184266 -0.735708 -0.676268 0.0373398 -0.735708 -0.58277 -0 -0.812637 -0.605223 -0.033417 -0.795355 -0.604014 -0.0507759 -0.795355 -0.199557 -0.0167756 -0.979743 -0.198976 -0.0226517 -0.979743 -0.323016 -0.0367727 -0.945679 -0.596914 -0.105377 -0.795355 -0.593245 -0.124381 -0.795355 -0.563043 -0.224484 -0.795355 -0.462618 -0.249083 -0.850848 -0.521771 -0.30849 -0.795355 -0.440942 -0.285705 -0.850848 -0.49444 -0.350629 -0.795355 -0.317126 -0.294303 -0.901563 -0.368449 -0.37457 -0.850848 -0.385121 -0.357405 -0.850848 -0.444298 -0.412323 -0.795355 -0.27322 -0.335461 -0.901563 -0.331801 -0.407388 -0.850848 -0.382785 -0.469986 -0.795355 -0.290835 -0.437575 -0.850848 -0.2688 -0.451447 -0.850848 -0.182681 -0.392187 -0.901563 -0.221851 -0.476277 -0.850848 -0.255939 -0.54946 -0.795355 -0.145218 -0.504945 -0.850848 -0.118352 -0.511908 -0.850848 -0.0909899 -0.517473 -0.850848 -0.0632419 -0.521592 -0.850848 -0.0352229 -0.52423 -0.850848 0.017415 -0.432296 -0.901563 0.0492588 -0.523098 -0.850848 0.021149 -0.524986 -0.850848 0.0405619 -0.430741 -0.901563 0.0771571 -0.519716 -0.850848 0.0635345 -0.427956 -0.901563 0.0890127 -0.599573 -0.795355 0.131854 -0.508598 -0.850848 0.158433 -0.500956 -0.850848 0.184364 -0.492004 -0.850848 0.192628 -0.387399 -0.901563 0.23393 -0.470462 -0.850848 0.269875 -0.542751 -0.795355 0.279943 -0.444623 -0.850848 0.265115 -0.341903 -0.901563 0.341374 -0.399401 -0.850848 0.321958 -0.415211 -0.850848 0.371429 -0.479011 -0.795355 0.414969 -0.441828 -0.795355 0.336023 -0.272529 -0.901563 0.422014 -0.312989 -0.850848 0.408071 -0.330962 -0.850848 0.470773 -0.381816 -0.795355 0.358111 -0.242777 -0.901563 0.446735 -0.276559 -0.850848 0.434894 -0.294831 -0.850848 0.501718 -0.340133 -0.795355 0.515379 -0.319054 -0.795355 0.54954 -0.255766 -0.795355 0.558792 -0.234866 -0.795355 0.567053 -0.214155 -0.795355 0.574369 -0.193678 -0.795355 0.58079 -0.173475 -0.795355 0.586365 -0.153581 -0.795355 0.591142 -0.134025 -0.795355 0.601155 -0.0776122 -0.795355 0.603205 -0.0596158 -0.795355 0.604684 -0.0420427 -0.795355 0.605633 -0.0248995 -0.795355 0.606089 -0.00819079 -0.795355 0.606089 0.00819068 -0.795355 0.605632 0.0248996 -0.795355 0.604684 0.0420427 -0.795355 0.603205 0.0596158 -0.795355 0.601155 0.077612 -0.795355 0.59849 0.0960216 -0.795355 0.595168 0.114831 -0.795355 0.418529 0.109621 -0.901563 0.503435 0.15037 -0.850848 0.508267 0.133125 -0.850848 0.586365 0.153581 -0.795355 0.58079 0.173475 -0.795355 0.574369 0.193678 -0.795355 0.3849 0.197574 -0.901563 0.457569 0.258241 -0.850848 0.467427 0.239936 -0.850848 0.53925 0.276804 -0.795355 0.367862 0.227731 -0.901563 0.434894 0.294831 -0.850848 0.446735 0.276559 -0.850848 0.515379 0.319054 -0.795355 0.347505 0.257729 -0.901563 0.408071 0.330962 -0.850848 0.422014 0.312989 -0.850848 0.486859 0.361081 -0.795355 0.453439 0.402249 -0.795355 0.359699 0.382981 -0.850848 0.265115 0.341903 -0.901563 0.301471 0.430316 -0.850848 0.321958 0.415211 -0.850848 0.371429 0.479011 -0.795355 0.279943 0.444623 -0.850848 0.257412 0.458035 -0.850848 0.172558 0.396746 -0.901563 0.209557 0.481812 -0.850848 0.241756 0.555846 -0.795355 0.131853 0.508598 -0.850848 0.104726 0.514869 -0.850848 0.0771571 0.519716 -0.850848 0.049259 0.523098 -0.850848 0.0211489 0.524986 -0.850848 -0.0290039 0.431674 -0.901563 -0.0632418 0.521592 -0.850848 -0.0352227 0.52423 -0.850848 -0.0520761 0.429501 -0.901563 -0.0729593 0.601737 -0.795355 -0.145218 0.504945 -0.850848 -0.171485 0.496639 -0.850848 -0.182681 0.392187 -0.901563 -0.221851 0.476277 -0.850848 -0.255939 0.54946 -0.795355 -0.2688 0.451447 -0.850848 -0.256788 0.3482 -0.901563 -0.311847 0.422858 -0.850848 -0.359764 0.487832 -0.795355 -0.303397 0.308437 -0.901563 -0.385122 0.357405 -0.850848 -0.368449 0.37457 -0.850848 -0.425063 0.432125 -0.795355 -0.462263 0.392076 -0.795355 -0.415176 0.322003 -0.850848 -0.49444 0.350629 -0.795355 -0.372424 0.220191 -0.901563 -0.462618 0.249083 -0.850848 -0.452276 0.267402 -0.850848 -0.407438 0.145527 -0.901563 -0.58885 0.143759 -0.795355 -0.593246 0.124381 -0.795355 -0.599902 0.0867661 -0.795355 -0.517411 0.0913422 -0.850848 -0.52204 0.0594298 -0.850848 -0.523565 0.044013 -0.850848 -0.60592 0.0164907 -0.795355 -0.605223 0.033417 -0.795355 -0.432487 -0.0117705 -0.901563 -0.524613 -0.0289662 -0.850848 -0.523565 -0.044013 -0.850848 -0.52204 -0.0594299 -0.850848 -0.520001 -0.0752096 -0.850848 -0.306159 -0.109352 -0.945679 -0.401883 -0.16023 -0.901563 -0.407438 -0.145527 -0.901563 -0.494797 -0.176729 -0.850848 -0.488051 -0.194585 -0.850848 -0.395637 -0.175085 -0.901563 -0.472002 -0.230806 -0.850848 -0.363092 -0.235262 -0.901563 -0.372424 -0.22019 -0.901563 -0.279849 -0.165457 -0.945679 -0.452276 -0.267402 -0.850848 -0.341875 -0.265152 -0.901563 -0.352916 -0.250268 -0.901563 -0.26519 -0.188058 -0.945679 -0.428585 -0.303928 -0.850848 -0.400694 -0.339855 -0.850848 -0.350673 -0.391261 -0.850848 -0.303397 -0.308437 -0.901563 -0.256789 -0.3482 -0.901563 -0.239486 -0.360319 -0.901563 -0.202391 -0.382389 -0.901563 -0.152082 -0.287337 -0.945679 -0.245787 -0.464378 -0.850848 -0.162266 -0.401065 -0.901563 -0.141208 -0.408954 -0.901563 -0.119579 -0.415794 -0.901563 -0.0974562 -0.421528 -0.901563 -0.0749251 -0.42611 -0.901563 -0.0058071 -0.432608 -0.901563 -0.0290041 -0.431674 -0.901563 -0.0217944 -0.324371 -0.945679 -0.00436361 -0.325073 -0.945679 -0.00705222 -0.525364 -0.850848 0.0862361 -0.423965 -0.901563 0.108574 -0.418802 -0.901563 0.13046 -0.412509 -0.901563 0.172558 -0.396746 -0.901563 0.129665 -0.298125 -0.945679 0.209557 -0.481813 -0.850848 0.211965 -0.377166 -0.901563 0.248245 -0.354342 -0.901563 0.186538 -0.266262 -0.945679 0.301471 -0.430317 -0.850848 0.310375 -0.301415 -0.901563 0.296192 -0.315363 -0.901563 0.222566 -0.236972 -0.945679 0.359699 -0.382981 -0.850848 0.393045 -0.348673 -0.850848 0.289224 -0.148462 -0.945679 0.392245 -0.182558 -0.901563 0.3849 -0.197574 -0.901563 0.467427 -0.239936 -0.850848 0.476347 -0.221701 -0.850848 0.484366 -0.203584 -0.850848 0.503434 -0.15037 -0.850848 0.508267 -0.133125 -0.850848 0.512407 -0.116174 -0.850848 0.429086 -0.0553972 -0.901563 0.522865 -0.0516756 -0.850848 0.521087 -0.067275 -0.850848 0.518777 -0.0832325 -0.850848 0.524146 -0.036443 -0.850848 0.524968 -0.0215831 -0.850848 0.525364 -0.00709986 -0.850848 0.525364 0.00709976 -0.850848 0.524968 0.0215833 -0.850848 0.524146 0.0364431 -0.850848 0.522864 0.0516756 -0.850848 0.521087 0.0672749 -0.850848 0.518777 0.0832325 -0.850848 0.515897 0.0995369 -0.850848 0.512407 0.116174 -0.850848 0.497869 0.167882 -0.850848 0.299705 0.125969 -0.945679 0.392245 0.182558 -0.901564 0.398849 0.16764 -0.901563 0.484367 0.203584 -0.850848 0.476347 0.221701 -0.850848 0.310375 0.301415 -0.901563 0.323651 0.287113 -0.901563 0.243199 0.215744 -0.945679 0.393045 0.348673 -0.850848 0.281102 0.328885 -0.901563 0.211227 0.247132 -0.945679 0.341374 0.399401 -0.850848 0.248245 0.354342 -0.901563 0.192628 0.387399 -0.901563 0.211965 0.377167 -0.901563 0.159276 0.283412 -0.945679 0.144746 0.291101 -0.945679 0.23393 0.470462 -0.850848 0.151813 0.405137 -0.901563 0.13046 0.412509 -0.901563 0.108574 0.418802 -0.901563 0.0862361 0.423965 -0.901563 0.0174149 0.432296 -0.901563 0.040562 0.430741 -0.901563 0.0304793 0.32367 -0.945679 -0.00580703 0.432608 -0.901563 0.0130861 0.324839 -0.945679 -0.00436356 0.325073 -0.945679 -0.00705213 0.525364 -0.850848 -0.0749252 0.42611 -0.901563 -0.0974562 0.421528 -0.901563 -0.119579 0.415794 -0.901563 -0.162266 0.401065 -0.901563 -0.121931 0.301371 -0.945679 -0.197058 0.487058 -0.850848 -0.202391 0.382389 -0.901563 -0.290835 0.437576 -0.850848 -0.221342 0.371741 -0.901563 -0.27322 0.335461 -0.901563 -0.350674 0.391261 -0.850848 -0.341875 0.265152 -0.901563 -0.329949 0.279852 -0.901563 -0.247933 0.210288 -0.945679 -0.400694 0.339855 -0.850848 -0.363092 0.235262 -0.901563 -0.352916 0.250268 -0.901563 -0.26519 0.188058 -0.945679 -0.428585 0.303928 -0.850848 -0.440942 0.285705 -0.850848 -0.297292 0.131563 -0.945679 -0.401883 0.16023 -0.901563 -0.395637 0.175085 -0.901563 -0.480467 0.212625 -0.850848 -0.488051 0.194585 -0.850848 -0.510421 0.124611 -0.850848 -0.514231 0.107815 -0.850848 -0.520001 0.0752096 -0.850848 -0.426059 0.0752152 -0.901563 -0.524612 0.0289662 -0.850848 -0.525217 0.0142943 -0.850848 -0.374395 -2.49655e-17 -0.927269 -0.431989 -0.023852 -0.901563 -0.431126 -0.0362422 -0.901563 -0.42987 -0.0489372 -0.901563 -0.428191 -0.0619308 -0.901563 -0.198199 -0.0286662 -0.979743 -0.0565528 -0.00643807 -0.998379 -0.0563315 -0.00814742 -0.998379 -0.197211 -0.0348151 -0.979743 -0.416613 -0.116692 -0.901563 -0.412336 -0.131005 -0.901563 -0.179905 -0.0879724 -0.979742 -0.286248 -0.154122 -0.945679 -0.292054 -0.142813 -0.945679 -0.388667 -0.190056 -0.901563 -0.38094 -0.205106 -0.901563 -0.152725 -0.129536 -0.979743 -0.238297 -0.221147 -0.945679 -0.247932 -0.210288 -0.945679 -0.329949 -0.279852 -0.901563 -0.205304 -0.252074 -0.945679 -0.216982 -0.242096 -0.945679 -0.13366 -0.14913 -0.979743 -0.28876 -0.322182 -0.901563 -0.192957 -0.261646 -0.945679 -0.166322 -0.279336 -0.945679 -0.102453 -0.172069 -0.979743 -0.221342 -0.371741 -0.901563 -0.137272 -0.2947 -0.945679 -0.121931 -0.301371 -0.945679 -0.106108 -0.307299 -0.945679 -0.0563007 -0.32019 -0.945679 -0.0732312 -0.316747 -0.945679 -0.04511 -0.195115 -0.979743 -0.0391314 -0.322739 -0.945679 -0.0346809 -0.197235 -0.979743 -0.0241047 -0.198805 -0.979743 -0.0520761 -0.429501 -0.901563 0.0130861 -0.324839 -0.945679 0.0304793 -0.32367 -0.945679 0.0477415 -0.321578 -0.945679 0.0648001 -0.318579 -0.945679 0.114076 -0.304431 -0.945679 0.0980313 -0.30997 -0.945679 0.0603867 -0.19094 -0.979743 0.0702703 -0.187527 -0.979743 0.151813 -0.405137 -0.901563 0.144746 -0.291102 -0.945679 0.159276 -0.283413 -0.945679 0.230517 -0.366122 -0.901563 0.199214 -0.256915 -0.945679 0.281102 -0.328885 -0.901563 0.14981 -0.132898 -0.979742 0.252496 -0.204785 -0.945679 0.243199 -0.215744 -0.945679 0.323651 -0.287113 -0.901563 0.347505 -0.257729 -0.901563 0.170274 -0.105411 -0.979743 0.283124 -0.159788 -0.945679 0.276421 -0.171123 -0.945679 0.367862 -0.227731 -0.901563 0.376782 -0.212647 -0.901563 0.398849 -0.16764 -0.901563 0.189763 -0.0639884 -0.979743 0.311504 -0.0930423 -0.945679 0.30806 -0.103878 -0.945679 0.409967 -0.138241 -0.901563 0.41455 -0.123821 -0.901563 0.418529 -0.109621 -0.901563 0.421938 -0.0956626 -0.901563 0.424812 -0.081963 -0.901563 0.427184 -0.0685373 -0.901563 0.430549 -0.0425519 -0.901563 0.431605 -0.0300088 -0.901563 0.432282 -0.0177725 -0.901563 0.432607 -0.00584634 -0.901563 0.432607 0.00584626 -0.901563 0.432282 0.0177726 -0.901563 0.323526 0.0319747 -0.945679 0.429086 0.0553971 -0.901563 0.430549 0.0425519 -0.901563 0.431605 0.0300088 -0.901563 0.427184 0.0685373 -0.901563 0.424812 0.081963 -0.901563 0.421938 0.0956625 -0.901563 0.191884 0.0573135 -0.979743 0.30806 0.103878 -0.945679 0.311504 0.0930424 -0.945679 0.41455 0.123821 -0.901563 0.409967 0.138241 -0.901563 0.404744 0.152857 -0.901563 0.289224 0.148462 -0.945679 0.376782 0.212647 -0.901563 0.276421 0.171123 -0.945679 0.358111 0.242776 -0.901563 0.261124 0.193664 -0.945679 0.336023 0.272529 -0.901563 0.233224 0.226491 -0.945679 0.296192 0.315363 -0.901563 0.199214 0.256915 -0.945679 0.106701 0.169469 -0.979743 0.173217 0.275113 -0.945679 0.230517 0.366122 -0.901563 0.129665 0.298125 -0.945679 0.114076 0.30443 -0.945679 0.0980312 0.30997 -0.945679 0.0477415 0.321577 -0.945679 0.0648 0.318579 -0.945679 0.0399165 0.196243 -0.979743 0.0294085 0.19809 -0.979743 0.0635345 0.427956 -0.901563 -0.0217943 0.324371 -0.945679 -0.0391313 0.322739 -0.945679 -0.0563008 0.32019 -0.945679 -0.0732312 0.316747 -0.945679 -0.106108 0.307299 -0.945679 -0.0653617 0.189295 -0.979743 -0.141208 0.408954 -0.901563 -0.137272 0.2947 -0.945679 -0.152082 0.287337 -0.945679 -0.192958 0.261647 -0.945679 -0.179956 0.270753 -0.945679 -0.110852 0.166782 -0.979743 -0.239486 0.360319 -0.901563 -0.133659 0.149129 -0.979743 -0.227981 0.231768 -0.945679 -0.216982 0.242096 -0.945679 -0.28876 0.322182 -0.901563 -0.317126 0.294303 -0.901563 -0.279849 0.165457 -0.945679 -0.38094 0.205106 -0.901563 -0.388667 0.190056 -0.901563 -0.315826 0.0771042 -0.945679 -0.313054 0.0876856 -0.945679 -0.420303 0.102611 -0.901563 -0.306159 0.109352 -0.945679 -0.42344 0.0887795 -0.901563 -0.428191 0.0619309 -0.901563 -0.42987 0.0489371 -0.901563 -0.431126 0.0362422 -0.901563 -0.323016 0.0367726 -0.945679 -0.323959 0.0272333 -0.945679 -0.432487 0.0117706 -0.901563 -0.431989 0.023852 -0.901563 0.536534 2.7244e-17 -0.843879 0.463238 0.0126074 -0.886144 0.470988 6.72016e-17 -0.882139 -0.324608 -0.017923 -0.945679 -0.32396 -0.0272334 -0.945679 -0.321754 -0.0465365 -0.945679 -0.320152 -0.0565186 -0.945679 -0.313054 -0.0876856 -0.945679 -0.30984 -0.0984407 -0.945679 -0.0528704 -0.0210793 -0.998379 -0.183131 -0.0810423 -0.979742 -0.186022 -0.0741664 -0.979742 -0.301985 -0.120401 -0.945679 -0.297292 -0.131563 -0.945679 -0.172386 -0.101921 -0.979743 -0.272836 -0.176782 -0.945679 -0.163356 -0.115843 -0.979743 -0.256893 -0.199242 -0.945679 -0.140435 -0.142768 -0.979743 -0.0399139 -0.040577 -0.998379 -0.22798 -0.231768 -0.945679 -0.126467 -0.155277 -0.979743 -0.0315061 -0.0474024 -0.998379 -0.110852 -0.166783 -0.979743 -0.179956 -0.270753 -0.945679 -0.0936819 -0.176998 -0.979743 -0.0845586 -0.181534 -0.979743 -0.0751089 -0.185643 -0.979743 -0.05535 -0.19246 -0.979743 -0.0157315 -0.0547009 -0.998379 -0.0898547 -0.312438 -0.945679 -0.0134253 -0.199811 -0.979743 -0.00268796 -0.200243 -0.979743 0.00806099 -0.200099 -0.979743 0.0187751 -0.199379 -0.979743 0.0294085 -0.19809 -0.979743 0.0502561 -0.193852 -0.979743 0.0142838 -0.0550967 -0.998379 0.0815854 -0.314699 -0.945679 0.0798727 -0.183643 -0.979743 0.0891625 -0.179317 -0.979743 0.0303261 -0.0481658 -0.998379 0.114906 -0.164015 -0.979743 0.1067 -0.169468 -0.979743 0.173217 -0.275114 -0.945679 0.0369809 -0.043267 -0.998379 0.1371 -0.145974 -0.979742 0.130115 -0.152233 -0.979742 0.211228 -0.247132 -0.945679 0.233224 -0.226491 -0.945679 0.0457166 -0.0339059 -0.998379 0.16576 -0.112375 -0.979743 0.160851 -0.119296 -0.979743 0.261124 -0.193664 -0.945679 0.269093 -0.182428 -0.945679 0.0516025 -0.0240167 -0.998379 0.184617 -0.0775964 -0.979743 0.18156 -0.0845015 -0.979743 0.294743 -0.137179 -0.945679 0.299705 -0.125969 -0.945679 0.304135 -0.114861 -0.945679 0.314494 -0.0823722 -0.945679 0.317055 -0.0718833 -0.945679 0.319215 -0.0615891 -0.945679 0.320997 -0.0515007 -0.945679 0.322426 -0.0416269 -0.945679 0.323526 -0.0319747 -0.945679 0.324319 -0.0225494 -0.945679 0.324828 -0.0133547 -0.945679 0.325073 -0.00439309 -0.945679 0.325073 0.00439303 -0.945679 0.324828 0.0133548 -0.945679 0.324319 0.0225494 -0.945679 0.0558874 0.0107829 -0.998379 -0.0973595 -0.0187845 -0.995072 0.0555093 0.0125852 -0.998379 0.322426 0.0416268 -0.945679 0.320997 0.0515007 -0.945679 0.319215 0.0615892 -0.945679 0.317056 0.0718833 -0.945679 0.314494 0.0823723 -0.945679 0.304136 0.114861 -0.945679 0.184617 0.0775962 -0.979743 0.294743 0.137179 -0.945679 0.0495682 0.0279751 -0.998379 0.170274 0.105411 -0.979742 0.174403 0.0984286 -0.979743 0.283124 0.159788 -0.945679 0.0471118 0.0319389 -0.998379 0.160851 0.119296 -0.979742 0.165761 0.112375 -0.979742 0.269093 0.182428 -0.945679 0.0442061 0.035853 -0.998379 0.14981 0.132898 -0.979742 0.155537 0.126147 -0.979742 0.252496 0.204785 -0.945679 0.038966 0.0414881 -0.998379 0.130115 0.152232 -0.979743 0.1371 0.145974 -0.979743 0.222566 0.236972 -0.945679 0.114906 0.164016 -0.979743 0.0326583 0.046616 -0.998379 0.186538 0.266261 -0.945679 0.098113 0.174581 -0.979743 0.0891627 0.179317 -0.979743 0.0798728 0.183644 -0.979743 0.0603868 0.19094 -0.979743 0.0171629 0.0542683 -0.998379 0.0502561 0.193853 -0.979743 0.0142836 0.0550962 -0.998379 0.0815852 0.314699 -0.945679 0.0187751 0.199379 -0.979743 0.00806094 0.200099 -0.979743 -0.00268793 0.200243 -0.979743 -0.0134252 0.199811 -0.979743 -0.0241047 0.198805 -0.979743 -0.04511 0.195115 -0.979743 -0.0128211 0.0554553 -0.998379 -0.05535 0.19246 -0.979743 -0.0157315 0.0547009 -0.998379 -0.0898547 0.312438 -0.945679 -0.0751089 0.185643 -0.979743 -0.0845587 0.181534 -0.979743 -0.102453 0.172069 -0.979743 -0.0291192 0.0489054 -0.998379 -0.166322 0.279336 -0.945679 -0.118861 0.161173 -0.979743 -0.205305 0.252075 -0.945679 -0.0417201 0.0387176 -0.998379 -0.152725 0.129536 -0.979743 -0.146789 0.136225 -0.979743 -0.238297 0.221147 -0.945679 -0.256894 0.199242 -0.945679 -0.163355 0.115842 -0.979743 -0.272836 0.176782 -0.945679 -0.0501152 0.0269831 -0.998379 -0.179905 0.0879723 -0.979742 -0.176328 0.0949386 -0.979742 -0.286248 0.154122 -0.945679 -0.292054 0.142813 -0.945679 -0.0528704 0.0210793 -0.998379 -0.188593 0.0673606 -0.979743 -0.186021 0.0741663 -0.979743 -0.301985 0.120401 -0.945679 -0.19086 0.060639 -0.979743 -0.320152 0.0565186 -0.945679 -0.318184 0.0667111 -0.945679 -0.321754 0.0465365 -0.945679 -0.198976 0.0226517 -0.979743 -0.199557 0.0167756 -0.979743 -0.324982 0.00884471 -0.945679 -0.324608 0.017923 -0.945679 -0.199956 -0.0110405 -0.979743 0.362771 0.00987314 -0.931826 0.392682 -3.68525e-17 -0.919674 -0.192839 -0.0540138 -0.979743 -0.19086 -0.0606391 -0.979742 -0.188593 -0.0673607 -0.979742 -0.0501152 -0.0269831 -0.998379 0.0873043 0.0470064 -0.995072 -0.0489949 -0.0289675 -0.998379 -0.176327 -0.0949383 -0.979743 -0.0477671 -0.0309503 -0.998379 0.0832138 0.0539176 -0.995072 -0.0464284 -0.0329244 -0.998379 -0.168066 -0.108897 -0.979743 -0.0449759 -0.0348825 -0.998379 0.0783512 0.0607678 -0.995072 -0.043407 -0.0368164 -0.998379 -0.158245 -0.122732 -0.979743 -0.14679 -0.136226 -0.979743 -0.0379883 -0.0423852 -0.998379 -0.0337823 -0.045808 -0.998379 0.0588511 0.0798009 -0.995072 -0.118861 -0.161173 -0.979743 -0.029119 -0.048905 -0.998379 -0.026626 -0.0503058 -0.998379 -0.0213472 -0.0527628 -0.998379 0.0371884 0.0919166 -0.995072 -0.0185769 -0.0538007 -0.998379 0.0323623 0.0937247 -0.995072 -0.0653617 -0.189295 -0.979743 -0.0128211 -0.0554553 -0.998379 -0.00985698 -0.0560581 -0.998379 -0.00685102 -0.0565043 -0.998379 -0.00381571 -0.05679 -0.998379 -0.00076397 -0.056913 -0.998379 0.00229109 -0.056872 -0.998379 0.00835846 -0.056301 -0.998379 -0.014561 0.0980801 -0.995072 0.011345 -0.055776 -0.998379 -0.0197638 0.0971654 -0.995072 0.0399165 -0.196243 -0.979743 0.0171631 -0.0542688 -0.998379 0.0199722 -0.053299 -0.998379 0.0227014 -0.052195 -0.998379 0.0278854 -0.0496188 -0.998379 -0.0485785 0.0864399 -0.995072 0.0981128 -0.17458 -0.979743 0.0326583 -0.046616 -0.998379 0.122715 -0.158258 -0.979743 0.038966 -0.0414881 -0.998379 0.143665 -0.139517 -0.979742 0.0425784 -0.0377716 -0.998379 0.155537 -0.126147 -0.979743 0.0483947 -0.0299595 -0.998379 0.174403 -0.0984288 -0.979743 0.17816 -0.0914519 -0.979743 0.187346 -0.0707537 -0.979743 -0.457558 0.0734105 -0.886144 -0.358322 0.0574891 -0.931826 -0.455018 0.0877909 -0.886144 0.191885 -0.0573136 -0.979743 0.193727 -0.0507409 -0.979743 0.195305 -0.0442798 -0.979743 0.196635 -0.0379386 -0.979743 0.197733 -0.0317242 -0.979743 0.198613 -0.0256419 -0.979743 0.19929 -0.0196962 -0.979743 0.199779 -0.0138903 -0.979743 0.200092 -0.00822644 -0.979743 0.200243 -0.00270612 -0.979743 0.200243 0.00270608 -0.979743 0.200092 0.00822648 -0.979743 0.199779 0.0138903 -0.979743 0.19929 0.0196962 -0.979743 0.198613 0.0256419 -0.979743 0.197733 0.0317242 -0.979743 0.196635 0.0379386 -0.979743 0.195305 0.0442798 -0.979743 0.193726 0.0507408 -0.979743 -0.0939572 -0.0316825 -0.995072 0.0532469 0.0201094 -0.998379 0.0539343 0.0181867 -0.998379 0.189763 0.0639883 -0.979743 0.187346 0.0707536 -0.979743 -0.0898956 -0.0418391 -0.995072 0.0506362 0.0259922 -0.998379 0.0516025 0.0240167 -0.998379 0.18156 0.0845013 -0.979743 0.17816 0.0914518 -0.979743 0.0408319 0.0396531 -0.998379 -0.0711322 -0.0690786 -0.995072 0.143665 0.139517 -0.979743 0.0369809 0.043267 -0.998379 0.122715 0.158258 -0.979743 0.0303261 0.0481658 -0.998379 0.0278854 0.0496188 -0.998379 0.0227012 0.0521946 -0.998379 -0.0395471 -0.0909267 -0.995072 0.0199721 0.0532985 -0.998379 -0.0347928 -0.0928499 -0.995072 0.0702705 0.187528 -0.979743 0.0113449 0.0557755 -0.998379 0.00835839 0.0563006 -0.998379 0.0053362 0.0566669 -0.998379 0.00229105 0.0568715 -0.998379 -0.000763954 0.0569125 -0.998379 -0.00685101 0.0565043 -0.998379 0.0119349 -0.0984337 -0.995072 -0.00985699 0.0560581 -0.998379 0.0171715 -0.0976564 -0.995072 -0.034681 0.197235 -0.979743 -0.018577 0.0538011 -0.998379 -0.0213474 0.0527632 -0.998379 -0.0266262 0.0503062 -0.998379 0.0463846 -0.0876368 -0.995072 -0.0936819 0.176998 -0.979743 -0.0315063 0.0474028 -0.998379 -0.0359442 0.0441326 -0.998379 0.0626172 -0.0768818 -0.995072 -0.0379886 0.0423855 -0.998379 -0.126466 0.155276 -0.979743 -0.140435 0.142768 -0.979743 -0.0449759 0.0348825 -0.998379 0.0783516 -0.060768 -0.995072 -0.0464284 0.0329244 -0.998379 -0.158245 0.122732 -0.979743 0.0832141 -0.0539179 -0.995072 -0.0489949 0.0289675 -0.998379 -0.0477671 0.0309503 -0.998379 -0.168066 0.108897 -0.979742 -0.172386 0.101921 -0.979742 -0.18313 0.0810422 -0.979743 -0.198199 0.0286663 -0.979743 -0.0565524 0.00643801 -0.998379 -0.0567176 0.00476791 -0.998379 -0.200187 0.0054483 -0.979743 -0.199957 0.0110405 -0.979743 0.0672886 -3.46053e-17 -0.997734 0.0991184 0.0026976 -0.995072 -0.0568315 -0.00313792 -0.998379 -0.056718 -0.00476795 -0.998379 0.239952 0.0273165 -0.9704 0.361629 0.0304 -0.931826 0.357379 0.0630905 -0.931826 -0.0552937 -0.0134991 -0.998379 -0.0536012 -0.019145 -0.998379 0.0921045 0.0367218 -0.995072 -0.0520488 -0.0230335 -0.998379 -0.0511318 -0.0250032 -0.998379 0.0726794 0.0674489 -0.995072 0.177018 0.164279 -0.9704 0.0695329 0.0706881 -0.995072 -0.0417201 -0.0387176 -0.998379 0.0626169 0.0768815 -0.995072 0.15251 0.187253 -0.9704 -0.0359439 -0.0441322 -0.998379 0.0548858 0.0825784 -0.995072 0.0507274 0.0851961 -0.995072 0.0418672 0.089882 -0.995072 0.101972 0.218917 -0.9704 -0.024033 -0.0515949 -0.998379 0.0274052 0.0952921 -0.995072 0.0223351 0.0966063 -0.995072 0.0171714 0.0976564 -0.995072 0.0119349 0.0984337 -0.995072 0.00133089 0.0991461 -0.995072 0.00324149 0.241479 -0.970401 -0.00399122 0.0990747 -0.995072 -0.00972098 0.241305 -0.970401 -0.00929607 0.0987183 -0.995072 -0.0226414 0.240437 -0.970401 0.00533623 -0.0566674 -0.998379 -0.0248832 0.095982 -0.995072 -0.0298992 0.0945398 -0.995072 -0.0347929 0.0928503 -0.995072 -0.044147 0.088785 -0.995072 -0.107524 0.216244 -0.9704 0.0253415 -0.0509649 -0.998379 -0.0528305 0.0839087 -0.995072 -0.0607596 0.0783582 -0.995072 -0.147986 0.190849 -0.9704 -0.0644237 0.0753745 -0.995072 0.0348776 -0.0449797 -0.998379 -0.0711322 0.0690786 -0.995072 -0.17325 0.168248 -0.9704 -0.0741746 0.0658009 -0.995072 0.0408319 -0.0396531 -0.998379 -0.0770103 0.0624585 -0.995072 -0.187567 0.152124 -0.9704 -0.0796415 0.0590666 -0.995072 0.0442061 -0.035853 -0.998379 -0.0820722 0.0556398 -0.995072 -0.199895 0.135517 -0.9704 -0.084307 0.0521917 -0.995072 0.0471118 -0.0319389 -0.998379 -0.0863514 0.0487347 -0.995072 -0.210318 0.118698 -0.9704 -0.0882119 0.0452802 -0.995072 0.0495682 -0.0279751 -0.998379 0.0506362 -0.0259922 -0.998379 -0.0914086 0.03842 -0.995072 -0.222635 0.093576 -0.9704 -0.0927599 0.035032 -0.995072 0.0524712 -0.0220542 -0.998379 0.0532469 -0.0201094 -0.998379 0.0539339 -0.0181866 -0.998379 0.0545369 -0.0162895 -0.998379 0.0550603 -0.0144214 -0.998379 0.0555089 -0.0125851 -0.998379 0.0558869 -0.0107828 -0.998379 0.0561989 -0.00901654 -0.998379 0.0564491 -0.00728787 -0.998379 0.0566417 -0.005598 -0.998379 0.056781 -0.00394789 -0.998379 0.05687 -0.00233811 -0.998379 0.0569129 -0.000769131 -0.998379 0.0569129 0.000769121 -0.998379 0.05687 0.00233812 -0.998379 0.056781 0.00394789 -0.998379 0.0566421 0.00559804 -0.998379 0.0564496 0.00728792 -0.998379 0.0561994 0.00901661 -0.998379 0.0550608 0.0144215 -0.998379 0.0545373 0.0162896 -0.998379 0.0524712 0.0220542 -0.998379 -0.0843074 -0.0521919 -0.995072 -0.205339 -0.127118 -0.9704 -0.0820726 -0.0556401 -0.995072 0.0483947 0.0299595 -0.998379 0.0457166 0.0339059 -0.998379 -0.0770103 -0.0624585 -0.995072 0.0425784 0.0377717 -0.998379 -0.0678817 -0.0722753 -0.995072 -0.0607593 -0.0783578 -0.995072 -0.147986 -0.190849 -0.9704 -0.0568931 -0.0812085 -0.995072 0.0348776 0.0449797 -0.998379 -0.0528303 -0.0839083 -0.995072 -0.0441468 -0.0887846 -0.995072 -0.107524 -0.216244 -0.9704 0.0253415 0.0509649 -0.998379 -0.0298991 -0.0945393 -0.995072 -0.0248831 -0.0959816 -0.995072 -0.0197637 -0.097165 -0.995072 -0.0145609 -0.0980797 -0.995072 -0.00929604 -0.0987179 -0.995072 0.00133086 -0.0991457 -0.995072 0.00324146 -0.24148 -0.9704 0.00664716 -0.0989316 -0.995072 0.0161899 -0.240959 -0.9704 -0.00381569 0.05679 -0.998379 0.0223351 -0.0966063 -0.995072 0.0274054 -0.0952926 -0.995072 0.0323624 -0.0937251 -0.995072 0.0418674 -0.0898824 -0.995072 0.101972 -0.218917 -0.970401 -0.0240332 0.0515953 -0.998379 0.0507276 -0.0851965 -0.995072 0.054886 -0.0825788 -0.995072 -0.0337825 0.0458084 -0.998379 0.0661787 -0.0738384 -0.995072 -0.0399139 0.040577 -0.998379 0.0726797 -0.0674491 -0.995072 -0.043407 0.0368164 -0.998379 0.0890752 -0.0435573 -0.995072 0.216952 -0.106088 -0.9704 0.0906727 -0.0401261 -0.995072 -0.0511318 0.0250032 -0.998379 -0.0520488 0.0230335 -0.998379 0.341759 -0.122068 -0.931826 -0.0536012 0.019145 -0.998379 -0.0542456 0.0172346 -0.998379 0.239014 -0.0345695 -0.9704 0.359167 -0.0519477 -0.931826 0.0933771 -0.033352 -0.995072 0.0944997 -0.030024 -0.995072 -0.0563315 0.00814743 -0.998379 0.0976447 -0.0172379 -0.995072 -0.0568966 0.0015485 -0.998379 -0.0568311 0.0031379 -0.998379 0.190685 1.03781e-16 -0.981651 0.241412 0.00657025 -0.9704 0.0990043 0.00546646 -0.995072 0.0988066 0.00830608 -0.995072 0.0985187 0.0112155 -0.995072 0.098134 0.0141935 -0.995072 0.096326 0.0235165 -0.995072 0.345868 0.109887 -0.931826 0.230164 0.0731264 -0.9704 0.349456 0.0978816 -0.931826 0.0945002 0.0300241 -0.995072 0.0933775 0.0333521 -0.995072 0.331861 0.146861 -0.931826 0.220843 0.0977313 -0.9704 0.3371 0.134401 -0.931826 0.0906727 0.0401261 -0.995072 0.0890752 0.0435573 -0.995072 0.212639 0.114489 -0.9704 0.0853526 0.0504635 -0.995072 0.202676 0.131322 -0.9704 0.0808817 0.0573567 -0.995072 0.190833 0.148006 -0.9704 0.0756182 0.0641368 -0.995072 0.169355 0.172168 -0.9704 0.0661784 0.073838 -0.995072 0.143338 0.194363 -0.9704 0.13368 0.201129 -0.9704 0.169766 0.320748 -0.931826 0.112974 0.213448 -0.9704 0.185662 0.311817 -0.931826 0.0463843 0.0876364 -0.995072 0.0905763 0.223873 -0.9704 0.0788219 0.228277 -0.9704 0.0667484 0.232094 -0.9704 0.0543997 0.235295 -0.9704 0.0436815 0.360266 -0.931826 0.0290686 0.239745 -0.970401 0.0628473 0.357422 -0.931826 0.0243287 0.362089 -0.931826 0.0161899 0.240958 -0.970401 0.00664723 0.098932 -0.995072 -0.0354647 0.238883 -0.9704 -0.0481366 0.236655 -0.9704 -0.0606055 0.233773 -0.9704 -0.127341 0.33983 -0.931826 -0.0847414 0.226146 -0.9704 -0.10943 0.346013 -0.931826 -0.144742 0.332791 -0.931826 -0.0963212 0.221461 -0.9704 -0.0395473 0.0909271 -0.995072 -0.118318 0.210532 -0.9704 -0.208228 0.297222 -0.931826 -0.138569 0.197792 -0.9704 -0.193358 0.307104 -0.931826 -0.0568933 0.0812088 -0.995072 -0.15691 0.183582 -0.9704 -0.0678819 0.0722756 -0.995072 -0.0898952 0.0418389 -0.995072 -0.0939567 0.0316823 -0.995072 -0.0950071 0.0283775 -0.995072 -0.0959191 0.0251231 -0.995072 -0.0967004 0.0219241 -0.995072 -0.097359 0.0187844 -0.995072 -0.0979026 0.0157075 -0.995072 -0.0983384 0.012696 -0.995072 -0.0986739 0.00975211 -0.995072 -0.0989158 0.00687746 -0.995072 -0.0990709 0.00407312 -0.995072 -0.0991456 0.00133987 -0.995072 -0.0991456 -0.00133985 -0.995072 -0.0990709 -0.00407315 -0.995072 -0.0989163 -0.00687749 -0.995072 -0.0986743 -0.00975216 -0.995072 -0.0983389 -0.012696 -0.995072 -0.097903 -0.0157075 -0.995072 -0.580311 -0.195682 -0.790537 -0.516893 -0.174297 -0.838118 -0.586799 -0.17527 -0.790537 -0.0967009 -0.0219242 -0.995072 -0.0959195 -0.0251232 -0.995072 -0.0950076 -0.0283776 -0.995072 -0.433523 -0.163726 -0.886144 -0.427208 -0.17956 -0.886144 -0.334555 -0.140617 -0.931826 -0.0927603 -0.0350322 -0.995072 -0.0914091 -0.0384202 -0.995072 -0.322855 -0.165725 -0.931826 -0.214849 -0.110285 -0.9704 -0.329016 -0.15313 -0.931826 -0.0882123 -0.0452805 -0.995072 -0.0863518 -0.0487349 -0.995072 -0.291487 -0.216183 -0.931826 -0.193975 -0.143863 -0.9704 -0.300384 -0.203641 -0.931826 -0.0796419 -0.0590669 -0.995072 -0.271478 -0.240831 -0.931826 -0.18066 -0.160265 -0.9704 -0.281857 -0.228597 -0.931826 -0.0741746 -0.0658009 -0.995072 -0.17325 -0.168248 -0.9704 -0.235789 -0.275869 -0.931826 -0.15691 -0.183582 -0.9704 -0.248446 -0.264527 -0.931826 -0.0644234 -0.0753742 -0.995072 -0.138569 -0.197792 -0.9704 -0.177796 -0.316367 -0.931826 -0.118318 -0.210532 -0.9704 -0.193358 -0.307103 -0.931826 -0.0485783 -0.0864395 -0.995072 -0.0963212 -0.221461 -0.9704 -0.0847415 -0.226146 -0.9704 -0.0728223 -0.23026 -0.9704 -0.0606055 -0.233774 -0.9704 -0.0532928 -0.35897 -0.931826 -0.0354647 -0.238884 -0.9704 -0.0723349 -0.355623 -0.931826 -0.0340234 -0.361307 -0.931826 -0.0226415 -0.240438 -0.9704 -0.0146077 -0.362611 -0.931826 -0.00972096 -0.241306 -0.9704 -0.00399118 -0.0990743 -0.995072 0.0290687 -0.239746 -0.9704 0.0418228 -0.237852 -0.970401 0.0543995 -0.235294 -0.970401 0.0667482 -0.232094 -0.970401 0.136109 -0.336414 -0.931826 0.0905761 -0.223872 -0.970401 0.118446 -0.343032 -0.931826 0.0371886 -0.091917 -0.995072 0.112974 -0.213448 -0.9704 0.123552 -0.207504 -0.9704 0.215395 -0.29207 -0.931826 0.143338 -0.194363 -0.9704 0.200881 -0.302236 -0.931826 0.0588514 -0.0798012 -0.995072 0.15251 -0.187253 -0.9704 0.25449 -0.258718 -0.931826 0.169355 -0.172168 -0.9704 0.242212 -0.270247 -0.931826 0.0695332 -0.0706884 -0.995072 0.177018 -0.164279 -0.9704 0.0756185 -0.0641371 -0.995072 0.190833 -0.148006 -0.9704 0.0808821 -0.057357 -0.995072 0.202676 -0.131322 -0.9704 0.085353 -0.0504638 -0.995072 0.0873042 -0.0470065 -0.995072 0.0921041 -0.0367217 -0.995072 0.0954799 -0.0267437 -0.995072 0.22743 -0.0812322 -0.9704 0.0970446 -0.0203466 -0.995072 0.0981335 -0.0141934 -0.995072 0.0985183 -0.0112155 -0.995072 0.0988061 -0.00830604 -0.995072 0.239952 -0.0273164 -0.9704 0.240653 -0.0202302 -0.9704 0.0991179 -0.0026976 -0.995072 0.0990038 -0.00546644 -0.995072 0.299575 -1.37491e-16 -0.954073 0.241134 0.0133141 -0.9704 0.240653 0.0202302 -0.9704 0.236362 0.0495562 -0.9704 0.234611 0.0572767 -0.9704 0.232551 0.065137 -0.9704 0.22743 0.0812322 -0.9704 0.224329 0.0894395 -0.9704 0.216952 0.106088 -0.9704 0.408026 0.219689 -0.886144 0.398904 0.235847 -0.886144 0.312389 0.184696 -0.931826 0.207885 0.122909 -0.9704 0.388908 0.25199 -0.886144 0.378009 0.268062 -0.886144 0.296026 0.209925 -0.931826 0.196996 0.139698 -0.9704 0.366183 0.284005 -0.886144 0.35341 0.29975 -0.886144 0.276762 0.23474 -0.931826 0.184176 0.156212 -0.9704 0.266006 0.246862 -0.931826 0.32497 0.330368 -0.886144 0.309292 0.34509 -0.886144 0.242212 0.270246 -0.931826 0.161184 0.17984 -0.9704 0.229177 0.281385 -0.931826 0.275047 0.372958 -0.886144 0.256515 0.385939 -0.886144 0.200881 0.302236 -0.931826 0.23708 0.398173 -0.886144 0.123552 0.207504 -0.9704 0.153233 0.328967 -0.931826 0.136109 0.336414 -0.931826 0.151249 0.438032 -0.886144 0.128081 0.445358 -0.886144 0.100303 0.348768 -0.931826 0.104386 0.4515 -0.886144 0.0817464 0.353578 -0.931826 0.0802525 0.456408 -0.886144 0.0418228 0.237852 -0.970401 0.00487101 0.362872 -0.931826 -0.0146078 0.362611 -0.931826 -0.0340234 0.361307 -0.931826 -0.0532928 0.358971 -0.931826 -0.0923678 0.454111 -0.886144 -0.116294 0.44858 -0.886144 -0.091072 0.351292 -0.931826 -0.139736 0.441839 -0.886144 -0.0728223 0.23026 -0.9704 -0.161577 0.324951 -0.931826 -0.227036 0.403984 -0.886144 -0.246908 0.392154 -0.886144 -0.128674 0.204367 -0.9704 -0.222378 0.286789 -0.931826 -0.317252 0.337786 -0.886144 -0.248446 0.264527 -0.931826 -0.301089 0.352269 -0.886144 -0.165333 0.176034 -0.9704 -0.332444 0.322846 -0.886144 -0.346663 0.307527 -0.886144 -0.271478 0.240831 -0.931826 -0.18066 0.160265 -0.9704 -0.281857 0.228597 -0.931826 -0.193975 0.143863 -0.9704 -0.300383 0.203641 -0.931826 -0.291487 0.216183 -0.931826 -0.205339 0.127118 -0.9704 -0.403572 0.227766 -0.886144 -0.412268 0.211622 -0.886144 -0.322854 0.165725 -0.931826 -0.214849 0.110285 -0.9704 -0.218949 0.101903 -0.9704 -0.439117 0.148071 -0.886144 -0.510309 0.192725 -0.838118 -0.516893 0.174297 -0.838118 -0.225926 0.0853241 -0.9704 -0.228841 0.0771656 -0.9704 -0.2314 0.0691163 -0.9704 -0.233621 0.06119 -0.9704 -0.235524 0.0533985 -0.9704 -0.237129 0.0457514 -0.9704 -0.238452 0.0382572 -0.9704 -0.239514 0.0309225 -0.9704 -0.240331 0.0237523 -0.9704 -0.24092 0.0167508 -0.9704 -0.241298 0.00992054 -0.9704 -0.24148 0.0032634 -0.9704 -0.241479 -0.00326335 -0.970401 -0.241297 -0.00992056 -0.970401 -0.240919 -0.0167507 -0.970401 -0.24033 -0.0237523 -0.970401 -0.239513 -0.0309223 -0.970401 -0.238452 -0.0382571 -0.970401 -0.237128 -0.0457514 -0.9704 -0.235524 -0.0533984 -0.9704 -0.233621 -0.06119 -0.9704 -0.2314 -0.0691163 -0.9704 -0.228841 -0.0771657 -0.9704 -0.225926 -0.0853241 -0.9704 -0.222635 -0.0935759 -0.9704 -0.218949 -0.101903 -0.9704 -0.210318 -0.118698 -0.9704 -0.308563 -0.191021 -0.931826 -0.316045 -0.178368 -0.931826 -0.199896 -0.135517 -0.9704 -0.187567 -0.152124 -0.9704 -0.332444 -0.322846 -0.886144 -0.317252 -0.337786 -0.886144 -0.165333 -0.176034 -0.9704 -0.222378 -0.286789 -0.931826 -0.265896 -0.379536 -0.886144 -0.246908 -0.392154 -0.886144 -0.128674 -0.204367 -0.9704 -0.161577 -0.32495 -0.931826 -0.144742 -0.332791 -0.931826 -0.162608 -0.433944 -0.886144 -0.139736 -0.44184 -0.886144 -0.10943 -0.346013 -0.931826 -0.116294 -0.44858 -0.886144 -0.0910719 -0.351291 -0.931826 -0.0923678 -0.454111 -0.886144 -0.0481367 -0.236656 -0.9704 0.00487095 -0.362872 -0.931826 0.0243285 -0.362089 -0.931826 0.0436815 -0.360266 -0.931826 0.0628474 -0.357422 -0.931826 0.104386 -0.4515 -0.886144 0.128081 -0.445358 -0.886144 0.100303 -0.348768 -0.931826 0.151248 -0.438032 -0.886144 0.0788216 -0.228276 -0.970401 0.153234 -0.328967 -0.931826 0.169766 -0.320748 -0.931826 0.23708 -0.398173 -0.886144 0.256514 -0.385939 -0.886144 0.13368 -0.201128 -0.9704 0.292647 -0.359314 -0.886144 0.309292 -0.34509 -0.886144 0.161184 -0.17984 -0.9704 0.339675 -0.315229 -0.886144 0.353409 -0.29975 -0.886144 0.276762 -0.23474 -0.931826 0.184176 -0.156212 -0.9704 0.366183 -0.284004 -0.886144 0.378009 -0.268062 -0.886144 0.296026 -0.209925 -0.931826 0.196996 -0.139698 -0.9704 0.469559 -0.27762 -0.838118 0.480295 -0.258601 -0.838118 0.408025 -0.21969 -0.886144 0.207885 -0.122909 -0.9704 0.212639 -0.114489 -0.9704 0.416302 -0.20357 -0.886144 0.423768 -0.187533 -0.886144 0.331861 -0.146861 -0.931826 0.220843 -0.0977313 -0.9704 0.224329 -0.0894395 -0.9704 0.234611 -0.0572767 -0.9704 0.360576 -0.0410485 -0.931826 0.361629 -0.0304 -0.931826 0.241135 -0.0133141 -0.9704 0.241412 -0.00657029 -0.9704 0.678166 1.27374e-16 -0.734909 0.71292 1.00793e-16 -0.701245 0.712809 0.0193997 -0.70109 0.362353 0.0200071 -0.931826 0.667118 0.0181562 -0.744731 0.612188 0.0166613 -0.790537 0.638204 1.0194e-16 -0.769868 0.606108 0.0876635 -0.790537 0.355182 0.0744683 -0.931826 0.352551 0.0860699 -0.931826 0.506701 0.20202 -0.838118 0.576731 0.205994 -0.790537 0.568868 0.226806 -0.790537 0.341759 0.122068 -0.931826 0.480295 0.258601 -0.838118 0.550161 0.269026 -0.790536 0.539223 0.290329 -0.790536 0.326015 0.159419 -0.931826 0.319532 0.172043 -0.931826 0.304561 0.197338 -0.931826 0.286765 0.222409 -0.931826 0.399838 0.371063 -0.838118 0.382528 0.388883 -0.838118 0.25449 0.258718 -0.931826 0.34448 0.422955 -0.838118 0.323763 0.439016 -0.838118 0.215394 0.29207 -0.931826 0.216782 0.409578 -0.886144 0.230328 0.494476 -0.838118 0.204588 0.50567 -0.838118 0.173804 0.429582 -0.886144 0.178038 0.515617 -0.838118 0.118446 0.343031 -0.931826 0.0557789 0.46004 -0.886144 0.0310664 0.462367 -0.886144 0.00622 0.463368 -0.886144 -0.0219572 0.545047 -0.838118 -0.0511411 0.543086 -0.838118 -0.0434459 0.461368 -0.886144 -0.0801054 0.539575 -0.838118 -0.068052 0.458385 -0.886144 -0.108728 0.534543 -0.838118 -0.072335 0.355623 -0.931826 -0.162608 0.433944 -0.886144 -0.184828 0.424955 -0.886144 -0.242869 0.488439 -0.838118 -0.267249 0.475538 -0.838118 -0.177796 0.316368 -0.931826 -0.265896 0.379536 -0.886144 -0.334261 0.431077 -0.838118 -0.354419 0.414663 -0.838118 -0.235789 0.275869 -0.931826 -0.260343 0.252827 -0.931826 -0.423664 0.343609 -0.838118 -0.43814 0.324949 -0.838118 -0.372213 0.276054 -0.886144 -0.451512 0.306097 -0.838118 -0.463806 0.287127 -0.838118 -0.394017 0.243923 -0.886144 -0.308562 0.191021 -0.931826 -0.316045 0.178368 -0.931826 -0.329015 0.15313 -0.931826 -0.334554 0.140617 -0.931826 -0.3395 0.128217 -0.931826 -0.34388 0.115957 -0.931826 -0.347725 0.103861 -0.931826 -0.351063 0.0919503 -0.931826 -0.353922 0.0802419 -0.931826 -0.356333 0.0687506 -0.931826 -0.359918 0.0464672 -0.931826 -0.361145 0.0356926 -0.931826 -0.362031 0.0251714 -0.931826 -0.362599 0.0149076 -0.931826 -0.362872 0.00490392 -0.931826 -0.362872 -0.00490385 -0.931826 -0.362599 -0.0149077 -0.931826 -0.362031 -0.0251714 -0.931826 -0.361145 -0.0356926 -0.931826 -0.359918 -0.0464672 -0.931826 -0.358322 -0.0574892 -0.931826 -0.356333 -0.0687507 -0.931826 -0.353923 -0.0802419 -0.931826 -0.351063 -0.0919504 -0.931826 -0.347725 -0.103861 -0.931826 -0.343881 -0.115957 -0.931826 -0.3395 -0.128217 -0.931826 -0.485288 -0.249105 -0.838118 -0.475053 -0.268109 -0.838118 -0.403572 -0.227766 -0.886144 -0.463806 -0.287127 -0.838118 -0.451512 -0.306097 -0.838118 -0.383573 -0.260038 -0.886144 -0.43814 -0.324949 -0.838118 -0.423664 -0.343609 -0.838118 -0.359915 -0.291906 -0.886144 -0.346663 -0.307527 -0.886144 -0.260343 -0.252827 -0.931826 -0.301089 -0.352269 -0.886144 -0.334261 -0.431077 -0.838118 -0.312991 -0.44676 -0.838118 -0.208228 -0.297222 -0.931826 -0.227036 -0.403984 -0.886144 -0.242869 -0.488439 -0.838118 -0.217564 -0.500223 -0.838118 -0.184828 -0.424956 -0.886144 -0.191409 -0.510804 -0.838118 -0.127341 -0.339829 -0.931826 -0.068052 -0.458386 -0.886144 -0.043446 -0.461369 -0.886144 -0.0186532 -0.463034 -0.886144 0.00621993 -0.463368 -0.886144 0.0365686 -0.544262 -0.838118 0.0656584 -0.541523 -0.838118 0.0557789 -0.46004 -0.886144 0.0944669 -0.537247 -0.838118 0.0802526 -0.456408 -0.886144 0.122874 -0.531469 -0.838118 0.0817464 -0.353578 -0.931826 0.173804 -0.429582 -0.886144 0.230328 -0.494476 -0.838118 0.255179 -0.482122 -0.838118 0.216782 -0.409578 -0.886144 0.279071 -0.468697 -0.838118 0.185662 -0.311817 -0.931826 0.323763 -0.439016 -0.838118 0.34448 -0.422955 -0.838118 0.229177 -0.281386 -0.931826 0.382528 -0.388883 -0.838118 0.399838 -0.371063 -0.838118 0.266006 -0.246862 -0.931826 0.286765 -0.222409 -0.931826 0.304562 -0.197338 -0.931826 0.31239 -0.184696 -0.931826 0.319533 -0.172043 -0.931826 0.326015 -0.159419 -0.931826 0.3371 -0.134401 -0.931826 0.594942 -0.145246 -0.790536 0.599383 -0.125668 -0.790536 0.53388 -0.111935 -0.838118 0.349455 -0.0978816 -0.931826 0.539871 -0.0780835 -0.838118 0.458637 -0.0663344 -0.886144 0.537182 -0.0948325 -0.838118 0.460436 -0.0524167 -0.886144 0.461781 -0.0388192 -0.886144 0.36277 -0.00987317 -0.931826 0.362353 -0.0200071 -0.931826 0.545287 0.0148405 -0.838118 0.462705 0.025548 -0.886144 0.461781 0.0388192 -0.886144 0.456353 0.0805631 -0.886144 0.453548 0.0950919 -0.886144 0.450188 0.109906 -0.886144 0.446235 0.124989 -0.886144 0.441654 0.14032 -0.886144 0.436408 0.155874 -0.886144 0.430458 0.171623 -0.886144 0.423768 0.187533 -0.886144 0.416302 0.20357 -0.886144 0.527169 0.311681 -0.790536 0.513959 0.333015 -0.790536 0.457792 0.296622 -0.838118 0.499555 0.354256 -0.790536 0.483926 0.375324 -0.790536 0.431041 0.334307 -0.838118 0.416005 0.352842 -0.838118 0.339675 0.315229 -0.886144 0.408742 0.456051 -0.790536 0.386745 0.474848 -0.790536 0.292647 0.359314 -0.886144 0.301948 0.454296 -0.838118 0.313311 0.526202 -0.790536 0.286487 0.541274 -0.790536 0.255179 0.482122 -0.838118 0.258587 0.555144 -0.790536 0.195671 0.420073 -0.886144 0.150767 0.52424 -0.838118 0.122874 0.531469 -0.838118 0.0944668 0.537247 -0.838118 0.0410555 0.611037 -0.790536 0.0365689 0.544262 -0.838118 0.0737142 0.607962 -0.790536 0.00822 0.61236 -0.790536 0.00732169 0.54544 -0.838118 -0.0246511 0.611919 -0.790536 -0.0186533 0.463034 -0.886144 -0.136892 0.528033 -0.838118 -0.164487 0.520098 -0.838118 -0.244257 0.561596 -0.790537 -0.217564 0.500224 -0.838118 -0.214893 0.573475 -0.790537 -0.272667 0.548366 -0.790537 -0.206325 0.414944 -0.886144 -0.29064 0.461613 -0.838118 -0.375271 0.483966 -0.790537 -0.351392 0.501573 -0.790537 -0.283965 0.366213 -0.886144 -0.419262 0.446398 -0.790537 -0.439338 0.426654 -0.790537 -0.391326 0.380029 -0.838118 -0.408064 0.361997 -0.838118 -0.359915 0.291906 -0.886144 -0.383573 0.260038 -0.886144 -0.564573 0.237296 -0.790536 -0.605044 0.281599 -0.744731 -0.61523 0.258588 -0.744731 -0.420135 0.195539 -0.886144 -0.427208 0.17956 -0.886144 -0.433523 0.163726 -0.886144 -0.444026 0.132625 -0.886144 -0.448288 0.117416 -0.886144 -0.45194 0.102465 -0.886144 -0.542844 0.0536502 -0.838118 -0.461163 0.0455775 -0.886144 -0.540999 0.0698457 -0.838118 -0.459595 0.0593361 -0.886144 -0.462294 0.0321425 -0.886144 -0.463019 0.0190362 -0.886144 -0.463367 0.00626203 -0.886144 -0.463367 -0.00626195 -0.886144 -0.463019 -0.0190363 -0.886144 -0.462293 -0.0321425 -0.886144 -0.461163 -0.0455775 -0.886144 -0.459595 -0.059336 -0.886144 -0.457558 -0.0734105 -0.886144 -0.455018 -0.0877908 -0.886144 -0.45194 -0.102464 -0.886144 -0.448288 -0.117416 -0.886144 -0.444026 -0.132625 -0.886144 -0.439117 -0.148071 -0.886144 -0.564573 -0.237296 -0.790537 -0.555225 -0.258412 -0.790537 -0.494549 -0.230172 -0.838118 -0.420135 -0.195538 -0.886144 -0.412267 -0.211622 -0.886144 -0.394017 -0.243923 -0.886144 -0.372213 -0.276054 -0.886144 -0.439338 -0.426655 -0.790536 -0.391326 -0.380029 -0.838118 -0.45813 -0.406411 -0.790536 -0.373444 -0.397615 -0.838118 -0.375272 -0.483966 -0.790536 -0.397902 -0.465538 -0.790536 -0.283965 -0.366213 -0.886144 -0.29064 -0.461612 -0.838118 -0.272667 -0.548366 -0.790536 -0.300037 -0.533882 -0.790536 -0.206325 -0.414944 -0.886144 -0.164487 -0.520098 -0.838118 -0.136892 -0.528033 -0.838118 -0.108728 -0.534543 -0.838118 -0.0574157 -0.609718 -0.790536 -0.0511412 -0.543086 -0.838118 -0.0899336 -0.605776 -0.790536 -0.024651 -0.611919 -0.790536 -0.0219571 -0.545047 -0.838118 0.0082199 -0.61236 -0.790536 0.0073216 -0.54544 -0.838118 0.0410553 -0.611037 -0.790536 0.0310662 -0.462367 -0.886144 0.150767 -0.52424 -0.838118 0.178038 -0.515617 -0.838118 0.258587 -0.555144 -0.790537 0.229689 -0.56771 -0.790536 0.195671 -0.420073 -0.886144 0.338995 -0.510034 -0.790537 0.363486 -0.492879 -0.790537 0.275047 -0.372958 -0.886144 0.364074 -0.406212 -0.838118 0.324969 -0.330368 -0.886144 0.467045 -0.396132 -0.790537 0.483926 -0.375324 -0.790537 0.431041 -0.334307 -0.838118 0.499555 -0.354256 -0.790537 0.513958 -0.333015 -0.790537 0.457792 -0.296622 -0.838118 0.388908 -0.25199 -0.886144 0.398904 -0.235847 -0.886144 0.576731 -0.205994 -0.790536 0.619911 -0.247157 -0.744731 0.628479 -0.224477 -0.744731 0.430458 -0.171623 -0.886144 0.436408 -0.155874 -0.886144 0.441654 -0.14032 -0.886144 0.446235 -0.12499 -0.886144 0.450188 -0.109906 -0.886144 0.543571 -0.0456948 -0.838118 0.463238 -0.0126075 -0.886144 0.462705 -0.025548 -0.886144 0.59158 5.13502e-17 -0.806246 0.544659 0.030073 -0.838118 0.543571 0.0456948 -0.838118 0.537182 0.0948325 -0.838118 0.533881 0.111935 -0.838118 0.529925 0.129373 -0.838118 0.525273 0.147128 -0.838118 0.519881 0.165174 -0.838118 0.513705 0.183482 -0.838118 0.498826 0.22075 -0.838118 0.490038 0.239626 -0.838118 0.469559 0.27762 -0.838118 0.444962 0.315542 -0.838118 0.508952 0.431676 -0.744731 0.489172 0.453968 -0.744731 0.448894 0.416589 -0.790536 0.429461 0.436596 -0.790536 0.364073 0.406212 -0.838118 0.363486 0.492879 -0.790536 0.369412 0.555798 -0.744731 0.341423 0.573416 -0.744731 0.279071 0.468697 -0.838118 0.229689 0.567711 -0.790536 0.199881 0.578878 -0.790536 0.13795 0.596676 -0.790536 0.184452 0.641368 -0.744731 0.150328 0.650213 -0.744731 0.106057 0.603162 -0.790536 0.115573 0.657281 -0.744731 0.0803283 0.662513 -0.744731 0.0656585 0.541523 -0.838118 -0.0574156 0.609717 -0.790537 -0.0899336 0.605775 -0.790537 -0.122068 0.600126 -0.790537 -0.184667 0.583909 -0.790537 -0.167477 0.646009 -0.744731 -0.201237 0.636302 -0.744731 -0.234174 0.624931 -0.744731 -0.191409 0.510804 -0.838118 -0.300037 0.533882 -0.790537 -0.355577 0.564749 -0.744731 -0.382922 0.546578 -0.744731 -0.312991 0.44676 -0.838118 -0.433605 0.50731 -0.744731 -0.456881 0.486453 -0.744731 -0.373444 0.397615 -0.838118 -0.499236 0.442876 -0.744731 -0.518321 0.42038 -0.744731 -0.475643 0.385766 -0.790536 -0.536031 0.397551 -0.744731 -0.552391 0.374487 -0.744731 -0.506908 0.343652 -0.790536 -0.567432 0.351279 -0.744731 -0.581193 0.328011 -0.744731 -0.533338 0.301003 -0.790536 -0.475053 0.268108 -0.838118 -0.485288 0.249104 -0.838118 -0.494549 0.230172 -0.838118 -0.502875 0.211364 -0.838118 -0.695423 0.157668 -0.70109 -0.733168 0.166225 -0.65942 -0.70016 0.135088 -0.70109 -0.522672 0.156116 -0.838118 -0.527689 0.138212 -0.838118 -0.531987 0.120613 -0.838118 -0.535611 0.10334 -0.838118 -0.538601 0.086413 -0.838118 -0.544175 0.0378356 -0.838118 -0.545028 0.0224079 -0.838118 -0.545439 0.00737116 -0.838118 -0.545439 -0.00737106 -0.838118 -0.545028 -0.022408 -0.838118 -0.544175 -0.0378356 -0.838118 -0.542844 -0.0536502 -0.838118 -0.658938 -0.10572 -0.744731 -0.65528 -0.126429 -0.744731 -0.601325 -0.116019 -0.790537 -0.540999 -0.0698456 -0.838118 -0.538601 -0.086413 -0.838118 -0.535611 -0.10334 -0.838118 -0.531987 -0.120613 -0.838118 -0.527689 -0.138212 -0.838118 -0.522672 -0.156116 -0.838118 -0.510309 -0.192725 -0.838118 -0.502875 -0.211364 -0.838118 -0.581193 -0.328011 -0.744731 -0.567432 -0.351279 -0.744731 -0.520711 -0.322355 -0.790537 -0.552391 -0.374487 -0.744731 -0.536031 -0.397551 -0.744731 -0.491895 -0.364817 -0.790537 -0.518321 -0.42038 -0.744731 -0.499236 -0.442876 -0.744731 -0.408064 -0.361997 -0.838118 -0.456881 -0.486453 -0.744731 -0.433605 -0.50731 -0.744731 -0.354418 -0.414663 -0.838118 -0.351392 -0.501573 -0.790536 -0.355577 -0.564749 -0.744731 -0.326959 -0.581785 -0.744731 -0.267248 -0.475538 -0.838118 -0.244257 -0.561596 -0.790536 -0.214893 -0.573475 -0.790536 -0.153687 -0.592817 -0.790536 -0.201237 -0.636302 -0.744731 -0.167477 -0.646009 -0.744731 -0.122068 -0.600126 -0.790536 -0.133021 -0.653974 -0.744731 -0.098003 -0.66013 -0.744731 -0.0801054 -0.539575 -0.838118 0.0737141 -0.607962 -0.790536 0.106057 -0.603162 -0.790536 0.13795 -0.596676 -0.790536 0.199881 -0.578878 -0.790536 0.184452 -0.641368 -0.744731 0.217816 -0.630819 -0.744731 0.250298 -0.618649 -0.744731 0.204588 -0.505669 -0.838118 0.286487 -0.541274 -0.790537 0.341423 -0.573416 -0.744731 0.369411 -0.555798 -0.744731 0.301948 -0.454296 -0.838118 0.386745 -0.474848 -0.790537 0.445417 -0.496971 -0.744731 0.467995 -0.47577 -0.744731 0.429461 -0.436595 -0.790537 0.448894 -0.416588 -0.790537 0.416006 -0.352842 -0.838118 0.444962 -0.315542 -0.838118 0.587606 -0.316379 -0.744731 0.599525 -0.293165 -0.744731 0.550161 -0.269026 -0.790536 0.490038 -0.239626 -0.838118 0.498826 -0.22075 -0.838118 0.506701 -0.20202 -0.838118 0.513705 -0.183482 -0.838118 0.51988 -0.165174 -0.838118 0.525272 -0.147128 -0.838118 0.529925 -0.129373 -0.838118 0.610263 -0.0513011 -0.790536 0.545287 -0.0148405 -0.838118 0.544659 -0.0300731 -0.838118 0.611483 0.0337627 -0.790537 0.74695 0.0850341 -0.65942 0.705729 0.102072 -0.70109 0.603089 0.106468 -0.790537 0.599383 0.125668 -0.790537 0.594942 0.145246 -0.790537 0.589719 0.165179 -0.790537 0.583665 0.185439 -0.790537 0.705453 0.344963 -0.619141 0.661927 0.356396 -0.65942 0.675355 0.330245 -0.65942 0.560027 0.247833 -0.790537 0.57447 0.339647 -0.744731 0.62785 0.338048 -0.70109 0.613815 0.36291 -0.70109 0.544378 0.386042 -0.744731 0.598434 0.38775 -0.70109 0.581662 0.412482 -0.70109 0.563465 0.437013 -0.70109 0.54381 0.461241 -0.70109 0.467045 0.396132 -0.790536 0.445417 0.496971 -0.744731 0.500048 0.508355 -0.70109 0.475924 0.531008 -0.70109 0.421446 0.517455 -0.744731 0.423229 0.57389 -0.70109 0.394713 0.593864 -0.70109 0.338995 0.510034 -0.790536 0.312192 0.589841 -0.744731 0.281789 0.604955 -0.744731 0.217816 0.630819 -0.744731 0.267441 0.661021 -0.70109 0.232734 0.674023 -0.70109 0.197085 0.685296 -0.70109 0.169265 0.588559 -0.790536 0.0447393 0.665864 -0.744731 0.00895755 0.667305 -0.744731 -0.026863 0.666824 -0.744731 -0.098003 0.66013 -0.744731 -0.0668526 0.709932 -0.70109 -0.104715 0.705342 -0.70109 -0.133021 0.653974 -0.744731 -0.142131 0.698764 -0.70109 -0.178948 0.690254 -0.70109 -0.153687 0.592817 -0.790537 -0.266174 0.611987 -0.744731 -0.297132 0.597569 -0.744731 -0.349352 0.621631 -0.70109 -0.37993 0.603428 -0.70109 -0.326299 0.518248 -0.790537 -0.408943 0.527391 -0.744731 -0.397902 0.465538 -0.790537 -0.511549 0.49678 -0.70109 -0.533429 0.473209 -0.70109 -0.45813 0.40641 -0.790536 -0.491895 0.364817 -0.790536 -0.520711 0.322355 -0.790536 -0.544829 0.279667 -0.790536 -0.555225 0.258412 -0.790536 -0.572919 0.21637 -0.790536 -0.580311 0.195682 -0.790536 -0.586799 0.17527 -0.790536 -0.592431 0.15517 -0.790536 -0.597257 0.135411 -0.790536 -0.601325 0.116019 -0.790536 -0.604682 0.097015 -0.790536 -0.607374 0.0784151 -0.790536 -0.609446 0.0602326 -0.790536 -0.61094 0.0424777 -0.790536 -0.611898 0.0251571 -0.790536 -0.612359 0.00827553 -0.790536 -0.612359 -0.00827542 -0.790536 -0.611898 -0.0251572 -0.790536 -0.61094 -0.0424777 -0.790536 -0.609446 -0.0602326 -0.790536 -0.607374 -0.078415 -0.790537 -0.604682 -0.097015 -0.790537 -0.597257 -0.135411 -0.790537 -0.592431 -0.15517 -0.790537 -0.698616 -0.358608 -0.619141 -0.711947 -0.331353 -0.619141 -0.738958 -0.343924 -0.57936 -0.572919 -0.21637 -0.790537 -0.646483 -0.300885 -0.70109 -0.634378 -0.325634 -0.70109 -0.593714 -0.304761 -0.744731 -0.544829 -0.279667 -0.790537 -0.533338 -0.301003 -0.790537 -0.506908 -0.343652 -0.790537 -0.475643 -0.385766 -0.790537 -0.511549 -0.49678 -0.70109 -0.488172 -0.519769 -0.70109 -0.419262 -0.446399 -0.790536 -0.408943 -0.527391 -0.744731 -0.409148 -0.584013 -0.70109 -0.37993 -0.603428 -0.70109 -0.326299 -0.518248 -0.790536 -0.297132 -0.597569 -0.744731 -0.234175 -0.624931 -0.744731 -0.284404 -0.653902 -0.70109 -0.250213 -0.667732 -0.70109 -0.21502 -0.679882 -0.70109 -0.184667 -0.583909 -0.790536 -0.0625675 -0.664426 -0.744731 -0.0268628 -0.666824 -0.744731 0.00895744 -0.667305 -0.744731 0.044739 -0.665864 -0.744731 0.115573 -0.657281 -0.744731 0.0858299 -0.707888 -0.70109 0.123489 -0.702299 -0.70109 0.150328 -0.650213 -0.744731 0.160624 -0.694747 -0.70109 0.197085 -0.685296 -0.70109 0.169265 -0.588559 -0.790536 0.281789 -0.604955 -0.744731 0.333574 -0.630239 -0.70109 0.364807 -0.612689 -0.70109 0.313311 -0.526202 -0.790537 0.3961 -0.537104 -0.744731 0.450311 -0.552895 -0.70109 0.475923 -0.531008 -0.70109 0.408742 -0.456051 -0.790537 0.508952 -0.431676 -0.744731 0.522675 -0.48506 -0.70109 0.54381 -0.461241 -0.70109 0.544378 -0.386042 -0.744731 0.563465 -0.437013 -0.70109 0.581662 -0.412482 -0.70109 0.57447 -0.339647 -0.744731 0.598434 -0.38775 -0.70109 0.613815 -0.36291 -0.70109 0.527169 -0.311681 -0.790537 0.539223 -0.290329 -0.790537 0.560028 -0.247833 -0.790536 0.568868 -0.226806 -0.790536 0.583665 -0.185439 -0.790536 0.589719 -0.165179 -0.790536 0.665019 -0.0559042 -0.744731 0.611484 -0.0337627 -0.790536 0.612188 -0.0166613 -0.790536 0.66635 0.0367921 -0.744731 0.660492 0.0955293 -0.744731 0.657203 0.116021 -0.744731 0.653164 0.136944 -0.744731 0.648324 0.158278 -0.744731 0.642632 0.18 -0.744731 0.628479 0.224477 -0.744731 0.619911 0.247157 -0.744731 0.610277 0.270071 -0.744731 0.599525 0.293165 -0.744731 0.587606 0.316379 -0.744731 0.560074 0.362895 -0.744731 0.527347 0.409001 -0.744731 0.551044 0.511387 -0.65942 0.522675 0.48506 -0.70109 0.467995 0.47577 -0.744731 0.474751 0.582904 -0.65942 0.450311 0.552895 -0.70109 0.3961 0.537104 -0.744731 0.364807 0.61269 -0.70109 0.351679 0.664445 -0.65942 0.301089 0.646389 -0.70109 0.333574 0.630239 -0.70109 0.31743 0.681472 -0.65942 0.250298 0.618649 -0.744731 0.160624 0.694747 -0.70109 0.123489 0.702299 -0.70109 0.08583 0.707888 -0.70109 0.050398 0.750084 -0.65942 0.00957105 0.713009 -0.70109 0.0478035 0.711469 -0.70109 0.0100905 0.751707 -0.65942 -0.0287028 0.712495 -0.70109 -0.0302607 0.751166 -0.65942 -0.0625674 0.664426 -0.744731 -0.21502 0.679882 -0.70109 -0.250213 0.667732 -0.70109 -0.29984 0.689392 -0.65942 -0.317483 0.638496 -0.70109 -0.284404 0.653901 -0.70109 -0.334714 0.673151 -0.65942 -0.326959 0.581785 -0.744731 -0.409148 0.584013 -0.70109 -0.460667 0.594097 -0.65942 -0.463302 0.542055 -0.70109 -0.436952 0.563512 -0.70109 -0.488172 0.519769 -0.70109 -0.478759 0.464937 -0.744731 -0.58388 0.47355 -0.65942 -0.572744 0.424779 -0.70109 -0.553821 0.449171 -0.70109 -0.622259 0.421852 -0.65942 -0.606296 0.375337 -0.70109 -0.590224 0.400135 -0.70109 -0.788096 0.297635 -0.538812 -0.800667 0.336529 -0.495662 -0.812503 0.306853 -0.495662 -0.593714 0.304761 -0.744731 -0.807189 0.241098 -0.538812 -0.814937 0.213448 -0.538812 -0.788475 0.206517 -0.57936 -0.624325 0.235785 -0.744731 -0.63238 0.213239 -0.744731 -0.63945 0.190996 -0.744731 -0.645588 0.169092 -0.744731 -0.650847 0.147561 -0.744731 -0.65528 0.126429 -0.744731 -0.658938 0.10572 -0.744731 -0.661872 0.085451 -0.744731 -0.664129 0.0656371 -0.744731 -0.665758 0.046289 -0.744731 -0.666802 0.0274144 -0.744731 -0.667304 0.00901807 -0.744731 -0.667304 -0.00901795 -0.744731 -0.666802 -0.0274145 -0.744731 -0.665758 -0.0462891 -0.744731 -0.664129 -0.0656371 -0.744731 -0.661872 -0.0854509 -0.744731 -0.762506 -0.287971 -0.57936 -0.798264 -0.269176 -0.538812 -0.788096 -0.297635 -0.538812 -0.650847 -0.147561 -0.744731 -0.645588 -0.169092 -0.744731 -0.63945 -0.190996 -0.744731 -0.63238 -0.21324 -0.744731 -0.624325 -0.235785 -0.744731 -0.615231 -0.258588 -0.744731 -0.605044 -0.281599 -0.744731 -0.639203 -0.395709 -0.65942 -0.590224 -0.400135 -0.70109 -0.606296 -0.375337 -0.70109 -0.60383 -0.447834 -0.65942 -0.553821 -0.449171 -0.70109 -0.572744 -0.424779 -0.70109 -0.533428 -0.473209 -0.70109 -0.478759 -0.464937 -0.744731 -0.463302 -0.542055 -0.70109 -0.460668 -0.594097 -0.65942 -0.436952 -0.563512 -0.70109 -0.382922 -0.546578 -0.744731 -0.349352 -0.621632 -0.70109 -0.334714 -0.673151 -0.65942 -0.317483 -0.638496 -0.70109 -0.266174 -0.611987 -0.744731 -0.178948 -0.690254 -0.70109 -0.142131 -0.698764 -0.70109 -0.104715 -0.705342 -0.70109 -0.0704812 -0.748464 -0.65942 -0.0287027 -0.712495 -0.70109 -0.0668527 -0.709932 -0.70109 -0.0302605 -0.751166 -0.65942 0.00957093 -0.713009 -0.70109 0.0100904 -0.751707 -0.65942 0.0478032 -0.711469 -0.70109 0.0503977 -0.750084 -0.65942 0.0803282 -0.662513 -0.744731 0.232734 -0.674024 -0.70109 0.267441 -0.66102 -0.70109 0.317431 -0.681472 -0.65942 0.301089 -0.646389 -0.70109 0.312192 -0.589841 -0.744731 0.394712 -0.593864 -0.70109 0.4462 -0.605038 -0.65942 0.423229 -0.57389 -0.70109 0.421446 -0.517455 -0.744731 0.527188 -0.535946 -0.65942 0.500048 -0.508355 -0.70109 0.489172 -0.453968 -0.744731 0.527347 -0.409 -0.744731 0.560074 -0.362895 -0.744731 0.802878 -0.255086 -0.538812 0.817909 -0.292137 -0.495662 0.827743 -0.262986 -0.495662 0.610277 -0.270071 -0.744731 0.723914 -0.202767 -0.65942 0.756177 -0.211803 -0.619141 0.730326 -0.178298 -0.65942 0.636035 -0.202078 -0.744731 0.642632 -0.18 -0.744731 0.648324 -0.158278 -0.744731 0.653163 -0.136944 -0.744731 0.702214 -0.123967 -0.70109 0.667118 -0.0181563 -0.744731 0.66635 -0.0367922 -0.744731 0.743643 3.97332e-16 -0.668577 0.711988 0.039312 -0.70109 0.702214 0.123967 -0.70109 0.697898 0.146323 -0.70109 0.692727 0.169119 -0.70109 0.716482 0.227637 -0.65942 0.671524 0.239851 -0.70109 0.662368 0.264085 -0.70109 0.652075 0.288568 -0.70109 0.640586 0.313243 -0.70109 0.684035 0.443214 -0.57936 0.640563 0.454251 -0.619141 0.659032 0.427014 -0.619141 0.644064 0.499524 -0.57936 0.598877 0.507947 -0.619141 0.620522 0.481265 -0.619141 0.573325 0.486275 -0.65942 0.501754 0.559829 -0.65942 0.524116 0.584779 -0.619141 0.416136 0.626096 -0.65942 0.434682 0.654 -0.619141 0.384607 0.645944 -0.65942 0.401748 0.674731 -0.619141 0.281956 0.696898 -0.65942 0.207782 0.72249 -0.65942 0.217043 0.75469 -0.619141 0.169342 0.732454 -0.65942 0.176889 0.765098 -0.619141 0.130191 0.740416 -0.65942 0.135993 0.773414 -0.619141 0.0904884 0.746309 -0.65942 0.0945212 0.77957 -0.619141 -0.070481 0.748464 -0.65942 -0.110399 0.743625 -0.65942 -0.18866 0.727718 -0.65942 -0.197068 0.76015 -0.619141 -0.22669 0.716783 -0.65942 -0.236793 0.748728 -0.619141 -0.263793 0.703974 -0.65942 -0.27555 0.735348 -0.619141 -0.400551 0.63618 -0.65942 -0.418402 0.664533 -0.619141 -0.431354 0.61571 -0.65942 -0.499454 0.644118 -0.57936 -0.510217 0.596944 -0.619141 -0.481198 0.620574 -0.619141 -0.584722 0.567841 -0.57936 -0.587444 0.521127 -0.619141 -0.563349 0.547085 -0.619141 -0.562381 0.498892 -0.65942 -0.620998 0.350476 -0.70109 -0.634378 0.325634 -0.70109 -0.646483 0.300885 -0.70109 -0.657367 0.276298 -0.70109 -0.667085 0.251934 -0.70109 -0.675692 0.227844 -0.70109 -0.683246 0.204077 -0.70109 -0.689804 0.180674 -0.70109 -0.704069 0.112961 -0.70109 -0.707203 0.0913036 -0.70109 -0.709616 0.0701325 -0.70109 -0.711356 0.0494594 -0.70109 -0.712471 0.029292 -0.70109 -0.713008 0.00963572 -0.70109 -0.713008 -0.00963559 -0.70109 -0.712471 -0.0292921 -0.70109 -0.711356 -0.0494594 -0.70109 -0.709616 -0.0701326 -0.70109 -0.707203 -0.0913034 -0.70109 -0.704069 -0.112961 -0.70109 -0.70016 -0.135088 -0.70109 -0.695423 -0.157667 -0.70109 -0.689804 -0.180674 -0.70109 -0.683246 -0.204077 -0.70109 -0.675692 -0.227844 -0.70109 -0.667085 -0.251933 -0.70109 -0.657367 -0.276298 -0.70109 -0.738462 -0.457157 -0.495662 -0.718887 -0.48736 -0.495662 -0.697293 -0.472721 -0.538812 -0.620998 -0.350476 -0.70109 -0.584722 -0.567841 -0.57936 -0.537606 -0.572402 -0.619141 -0.563349 -0.547085 -0.619141 -0.514668 -0.54798 -0.65942 -0.488448 -0.571475 -0.65942 -0.499454 -0.644118 -0.57936 -0.450579 -0.643151 -0.619141 -0.481198 -0.620574 -0.619141 -0.400551 -0.63618 -0.65942 -0.418402 -0.664533 -0.619141 -0.368313 -0.655371 -0.65942 -0.362896 -0.729828 -0.57936 -0.313203 -0.720116 -0.619141 -0.349631 -0.703151 -0.619141 -0.29984 -0.689392 -0.65942 -0.22669 -0.716783 -0.65942 -0.236793 -0.748728 -0.619141 -0.18866 -0.727718 -0.65942 -0.197068 -0.76015 -0.619141 -0.149845 -0.73669 -0.65942 -0.156524 -0.769522 -0.619141 -0.110399 -0.743625 -0.65942 -0.115319 -0.776766 -0.619141 0.0904883 -0.746309 -0.65942 0.169342 -0.732454 -0.65942 0.176889 -0.765098 -0.619141 0.207782 -0.72249 -0.65942 0.217043 -0.75469 -0.619141 0.245366 -0.710606 -0.65942 0.256301 -0.742276 -0.619141 0.281957 -0.696897 -0.65942 0.367352 -0.694058 -0.619141 0.331578 -0.711843 -0.619141 0.344157 -0.738849 -0.57936 0.351679 -0.664445 -0.65942 0.416136 -0.626097 -0.65942 0.434682 -0.654 -0.619141 0.501754 -0.559829 -0.65942 0.524116 -0.584779 -0.619141 0.644064 -0.499524 -0.57936 0.640563 -0.454251 -0.619141 0.620522 -0.481265 -0.619141 0.684035 -0.443214 -0.57936 0.675971 -0.399659 -0.619141 0.659032 -0.427014 -0.619141 0.780228 -0.381527 -0.495662 0.794221 -0.351473 -0.495662 0.770363 -0.340915 -0.538812 0.62785 -0.338048 -0.70109 0.640587 -0.313243 -0.70109 0.652075 -0.288568 -0.70109 0.662368 -0.264085 -0.70109 0.671524 -0.239851 -0.70109 0.679597 -0.215918 -0.70109 0.686646 -0.192328 -0.70109 0.692727 -0.169119 -0.70109 0.697898 -0.146323 -0.70109 0.78252 -0.0657817 -0.619141 0.78024 -0.0888237 -0.619141 0.712809 -0.0193998 -0.70109 0.750632 0.0414457 -0.65942 0.744033 0.107612 -0.65942 0.756177 0.211803 -0.619141 0.762874 0.186244 -0.619141 0.791817 0.19331 -0.57936 0.740327 0.130695 -0.65942 0.735777 0.154265 -0.65942 0.730326 0.178298 -0.65942 0.723914 0.202766 -0.65942 0.794221 0.351473 -0.495662 0.780228 0.381527 -0.495662 0.756791 0.370067 -0.538812 0.707971 0.252869 -0.65942 0.698319 0.278418 -0.65942 0.687466 0.30423 -0.65942 0.64713 0.382607 -0.65942 0.630914 0.408795 -0.65942 0.613232 0.43487 -0.65942 0.594047 0.460732 -0.65942 0.562257 0.627334 -0.538812 0.544001 0.606964 -0.57936 0.590758 0.600572 -0.538812 0.527188 0.535946 -0.65942 0.466086 0.632003 -0.619141 0.483769 0.65598 -0.57936 0.4462 0.605038 -0.65942 0.331577 0.711843 -0.619141 0.344157 0.738849 -0.57936 0.294522 0.727956 -0.619141 0.305696 0.755574 -0.57936 0.256301 0.742276 -0.619141 0.232837 0.80961 -0.538812 0.225277 0.783321 -0.57936 0.274953 0.796293 -0.538812 0.245366 0.710606 -0.65942 0.0105402 0.785209 -0.619141 0.0109401 0.814998 -0.57936 -0.0316093 0.784643 -0.619141 -0.0328085 0.814411 -0.57936 -0.0736222 0.781821 -0.619141 -0.0764153 0.811482 -0.57936 -0.115319 0.776766 -0.619141 -0.119694 0.806235 -0.57936 -0.156524 0.769522 -0.619141 -0.162462 0.798717 -0.57936 -0.149845 0.73669 -0.65942 -0.349631 0.703151 -0.619141 -0.362896 0.729828 -0.57936 -0.384728 0.684579 -0.619141 -0.399324 0.710551 -0.57936 -0.368313 0.655371 -0.65942 -0.576728 0.614057 -0.538812 -0.558002 0.594118 -0.57936 -0.547347 0.640385 -0.538812 -0.488448 0.571475 -0.65942 -0.514668 0.54798 -0.65942 -0.539313 0.523743 -0.65942 -0.716279 0.443425 -0.538812 -0.718887 0.487361 -0.495662 -0.738462 0.457157 -0.495662 -0.60383 0.447834 -0.65942 -0.749456 0.384705 -0.538812 -0.75637 0.426877 -0.495662 -0.772666 0.396619 -0.495662 -0.639203 0.395709 -0.65942 -0.654703 0.369499 -0.65942 -0.668809 0.343308 -0.65942 -0.681571 0.317216 -0.65942 -0.693046 0.291295 -0.65942 -0.703291 0.265607 -0.65942 -0.712365 0.24021 -0.65942 -0.720329 0.215154 -0.65942 -0.727244 0.19048 -0.65942 -0.775364 0.124399 -0.619141 -0.745587 0.0962591 -0.65942 -0.742282 0.119092 -0.65942 -0.738161 0.14242 -0.65942 -0.74813 0.073939 -0.65942 -0.749964 0.0521438 -0.65942 -0.75114 0.0308818 -0.65942 -0.751706 0.0101587 -0.65942 -0.751706 -0.0101586 -0.65942 -0.75114 -0.030882 -0.65942 -0.749964 -0.0521438 -0.65942 -0.74813 -0.073939 -0.65942 -0.745587 -0.0962589 -0.65942 -0.742282 -0.119092 -0.65942 -0.738161 -0.14242 -0.65942 -0.733168 -0.166225 -0.65942 -0.727244 -0.19048 -0.65942 -0.720329 -0.215154 -0.65942 -0.712365 -0.240211 -0.65942 -0.703291 -0.265607 -0.65942 -0.693046 -0.291295 -0.65942 -0.681572 -0.317216 -0.65942 -0.668809 -0.343308 -0.65942 -0.654703 -0.369499 -0.65942 -0.654286 -0.530652 -0.538812 -0.697597 -0.517376 -0.495662 -0.674549 -0.547086 -0.495662 -0.622259 -0.421852 -0.65942 -0.630194 -0.55905 -0.538812 -0.609731 -0.540898 -0.57936 -0.58388 -0.47355 -0.65942 -0.562381 -0.498892 -0.65942 -0.539313 -0.523743 -0.65942 -0.448851 -0.712892 -0.538812 -0.434276 -0.689744 -0.57936 -0.483368 -0.689954 -0.538812 -0.431354 -0.61571 -0.65942 -0.325086 -0.747437 -0.57936 -0.27555 -0.735348 -0.619141 -0.286004 -0.763246 -0.57936 -0.263793 -0.703973 -0.65942 -0.0316092 -0.784643 -0.619141 -0.0328083 -0.814411 -0.57936 0.0105401 -0.785209 -0.619141 0.01094 -0.814998 -0.57936 0.0526438 -0.783513 -0.619141 0.0546411 -0.813238 -0.57936 0.0945211 -0.77957 -0.619141 0.0981071 -0.809146 -0.57936 0.135994 -0.773414 -0.619141 0.141153 -0.802756 -0.57936 0.130191 -0.740416 -0.65942 0.381289 -0.720389 -0.57936 0.401748 -0.674732 -0.619141 0.466314 -0.701593 -0.538812 0.451173 -0.678812 -0.57936 0.430984 -0.723833 -0.538812 0.384607 -0.645944 -0.65942 0.49591 -0.608882 -0.619141 0.514724 -0.631982 -0.57936 0.474752 -0.582904 -0.65942 0.642459 -0.544912 -0.538812 0.621598 -0.527218 -0.57936 0.61749 -0.573051 -0.538812 0.551044 -0.511387 -0.65942 0.573325 -0.486275 -0.65942 0.594047 -0.460732 -0.65942 0.613232 -0.43487 -0.65942 0.630914 -0.408795 -0.65942 0.64713 -0.382607 -0.65942 0.661927 -0.356396 -0.65942 0.675355 -0.330245 -0.65942 0.687466 -0.30423 -0.65942 0.698319 -0.278418 -0.65942 0.707971 -0.252869 -0.65942 0.716482 -0.227637 -0.65942 0.735777 -0.154265 -0.65942 0.750632 -0.0414457 -0.65942 0.751497 -0.0204528 -0.65942 0.78252 0.0657818 -0.619141 0.784086 0.0432928 -0.619141 0.78024 0.0888238 -0.619141 0.777193 0.112408 -0.619141 0.773322 0.13652 -0.619141 0.768569 0.16114 -0.619141 0.748414 0.237782 -0.619141 0.739523 0.264139 -0.619141 0.729441 0.290826 -0.619141 0.718105 0.317789 -0.619141 0.747621 0.44202 -0.495662 0.725163 0.428742 -0.538812 0.764716 0.411739 -0.495662 0.691428 0.372279 -0.619141 0.675971 0.399658 -0.619141 0.609053 0.619172 -0.495662 0.636613 0.590798 -0.495662 0.575602 0.534178 -0.619141 0.550683 0.559832 -0.619141 0.515489 0.698992 -0.495662 0.500004 0.677995 -0.538812 0.548474 0.673421 -0.495662 0.49591 0.608882 -0.619141 0.466314 0.701593 -0.538812 0.430984 0.723833 -0.538812 0.41699 0.70033 -0.57936 0.366723 0.787295 -0.495662 0.355707 0.763645 -0.538812 0.40629 0.767625 -0.495662 0.367352 0.694058 -0.619141 0.189761 0.820776 -0.538812 0.1836 0.794124 -0.57936 0.14589 0.829697 -0.538812 0.141153 0.802756 -0.57936 0.1014 0.836301 -0.538812 0.0981072 0.809146 -0.57936 0.0116574 0.868437 -0.495662 0.0113073 0.84235 -0.538812 0.0582242 0.866562 -0.495662 0.0526441 0.783513 -0.619141 -0.211409 0.815468 -0.538812 -0.254025 0.803214 -0.538812 -0.245777 0.777133 -0.57936 -0.295602 0.788861 -0.538812 -0.286004 0.763246 -0.57936 -0.386691 0.777682 -0.495662 -0.375075 0.754321 -0.538812 -0.346401 0.796445 -0.495662 -0.313203 0.720116 -0.619141 -0.44885 0.712892 -0.538812 -0.483368 0.689954 -0.538812 -0.467673 0.667551 -0.57936 -0.450579 0.643151 -0.619141 -0.537606 0.572402 -0.619141 -0.697597 0.517376 -0.495662 -0.676641 0.501835 -0.538812 -0.674549 0.547086 -0.495662 -0.609902 0.494655 -0.619141 -0.630741 0.467793 -0.619141 -0.649991 0.440653 -0.619141 -0.66769 0.413345 -0.619141 -0.683882 0.385966 -0.619141 -0.698616 0.358608 -0.619141 -0.711947 0.331354 -0.619141 -0.723933 0.304277 -0.619141 -0.734635 0.277445 -0.619141 -0.744114 0.250916 -0.619141 -0.752433 0.224743 -0.619141 -0.759655 0.198969 -0.619141 -0.765843 0.173633 -0.619141 -0.771059 0.148768 -0.619141 -0.778816 0.100549 -0.619141 -0.781472 0.0772343 -0.619141 -0.785208 0.0106114 -0.619141 -0.784617 0.0322581 -0.619141 -0.814384 0.0334819 -0.57936 -0.783388 0.0544677 -0.619141 -0.785208 -0.0106113 -0.619141 -0.784617 -0.0322583 -0.619141 -0.783388 -0.0544677 -0.619141 -0.775364 -0.124399 -0.619141 -0.778816 -0.100549 -0.619141 -0.808363 -0.104364 -0.57936 -0.781472 -0.0772343 -0.619141 -0.771059 -0.148768 -0.619141 -0.765843 -0.173633 -0.619141 -0.759655 -0.198969 -0.619141 -0.752433 -0.224743 -0.619141 -0.744114 -0.250916 -0.619141 -0.734635 -0.277445 -0.619141 -0.723934 -0.304277 -0.619141 -0.683882 -0.385966 -0.619141 -0.66769 -0.413345 -0.619141 -0.649991 -0.440653 -0.619141 -0.630741 -0.467793 -0.619141 -0.609902 -0.494655 -0.619141 -0.587444 -0.521127 -0.619141 -0.576728 -0.614057 -0.538812 -0.547347 -0.640386 -0.538812 -0.529574 -0.619592 -0.57936 -0.510217 -0.596945 -0.619141 -0.412725 -0.734397 -0.538812 -0.399324 -0.710551 -0.57936 -0.384728 -0.684579 -0.619141 -0.254025 -0.803214 -0.538812 -0.211409 -0.815468 -0.538812 -0.204544 -0.788989 -0.57936 -0.167914 -0.825522 -0.538812 -0.162462 -0.798717 -0.57936 -0.123711 -0.833293 -0.538812 -0.119694 -0.806235 -0.57936 -0.07898 -0.838716 -0.538812 -0.0764154 -0.811482 -0.57936 -0.0736223 -0.781821 -0.619141 0.189761 -0.820776 -0.538812 0.232837 -0.80961 -0.538812 0.225277 -0.783321 -0.57936 0.274953 -0.796293 -0.538812 0.266025 -0.770437 -0.57936 0.315956 -0.780931 -0.538812 0.305696 -0.755574 -0.57936 0.294523 -0.727956 -0.619141 0.548474 -0.673421 -0.495662 0.531998 -0.653192 -0.538812 0.515489 -0.698992 -0.495662 0.466086 -0.632003 -0.619141 0.636614 -0.590798 -0.495662 0.609053 -0.619172 -0.495662 0.550683 -0.559832 -0.619141 0.575603 -0.534178 -0.619141 0.598877 -0.507947 -0.619141 0.691428 -0.372279 -0.619141 0.705454 -0.344963 -0.619141 0.718105 -0.317789 -0.619141 0.729441 -0.290826 -0.619141 0.739523 -0.264139 -0.619141 0.748414 -0.237782 -0.619141 0.773322 -0.13652 -0.619141 0.768569 -0.16114 -0.619141 0.797727 -0.167253 -0.57936 0.762874 -0.186244 -0.619141 0.777193 -0.112408 -0.619141 0.809841 -0.0921935 -0.57936 0.784989 -0.0213643 -0.619141 0.784085 -0.0432928 -0.619141 0.813832 0.0449353 -0.57936 0.806678 0.116673 -0.57936 0.80266 0.141699 -0.57936 0.797727 0.167253 -0.57936 0.844319 0.295444 -0.447033 0.817909 0.292137 -0.495662 0.827743 0.262986 -0.495662 0.784865 0.219839 -0.57936 0.776808 0.246803 -0.57936 0.76758 0.27416 -0.57936 0.757115 0.30186 -0.57936 0.745349 0.329845 -0.57936 0.732217 0.35805 -0.57936 0.717659 0.386403 -0.57936 0.701617 0.414821 -0.57936 0.686294 0.532277 -0.495662 0.714727 0.53789 -0.447033 0.69936 0.557725 -0.447033 0.664865 0.471484 -0.57936 0.662355 0.561787 -0.495662 0.642458 0.544912 -0.538812 0.621597 0.527218 -0.57936 0.59744 0.554444 -0.57936 0.571575 0.581071 -0.57936 0.514724 0.631982 -0.57936 0.480756 0.723321 -0.495662 0.451173 0.678812 -0.57936 0.381289 0.720389 -0.57936 0.32574 0.805116 -0.495662 0.315955 0.780931 -0.538812 0.283468 0.820954 -0.495662 0.266025 0.770437 -0.57936 0.0546414 0.813238 -0.57936 -0.0349598 0.867812 -0.495662 -0.0339096 0.841743 -0.538812 -0.0814258 0.86469 -0.495662 -0.0789798 0.838716 -0.538812 -0.127542 0.8591 -0.495662 -0.123711 0.833293 -0.538812 -0.173114 0.851088 -0.495662 -0.167914 0.825522 -0.538812 -0.217956 0.840723 -0.495662 -0.204545 0.788989 -0.57936 -0.325086 0.747437 -0.57936 -0.425507 0.757141 -0.495662 -0.412726 0.734397 -0.538812 -0.462751 0.73497 -0.495662 -0.434276 0.689744 -0.57936 -0.532203 0.686352 -0.495662 -0.564298 0.660218 -0.495662 -0.529574 0.619592 -0.57936 -0.623061 0.605074 -0.495662 -0.649711 0.576364 -0.495662 -0.630194 0.55905 -0.538812 -0.609731 0.540897 -0.57936 -0.633041 0.513422 -0.57936 -0.65467 0.48554 -0.57936 -0.674651 0.457371 -0.57936 -0.693021 0.429027 -0.57936 -0.709827 0.400609 -0.57936 -0.72512 0.372213 -0.57936 -0.738958 0.343925 -0.57936 -0.751398 0.315821 -0.57936 -0.762506 0.287971 -0.57936 -0.772344 0.260435 -0.57936 -0.780979 0.233269 -0.57936 -0.794898 0.180221 -0.57936 -0.800312 0.154412 -0.57936 -0.80478 0.129119 -0.57936 -0.808363 0.104364 -0.57936 -0.81112 0.0801644 -0.57936 -0.813109 0.0565341 -0.57936 -0.814997 0.011014 -0.57936 -0.814997 -0.0110139 -0.57936 -0.814384 -0.0334821 -0.57936 -0.813109 -0.0565341 -0.57936 -0.81112 -0.0801644 -0.57936 -0.80478 -0.129119 -0.57936 -0.866163 -0.223434 -0.447033 -0.840175 -0.220059 -0.495662 -0.847019 -0.192037 -0.495662 -0.800312 -0.154412 -0.57936 -0.794898 -0.18022 -0.57936 -0.788475 -0.206517 -0.57936 -0.780979 -0.233269 -0.57936 -0.772344 -0.260436 -0.57936 -0.751399 -0.315821 -0.57936 -0.75637 -0.426877 -0.495662 -0.772666 -0.396619 -0.495662 -0.782902 -0.432696 -0.447033 -0.72512 -0.372213 -0.57936 -0.709827 -0.400609 -0.57936 -0.693021 -0.429027 -0.57936 -0.674651 -0.457371 -0.57936 -0.65467 -0.48554 -0.57936 -0.633041 -0.513422 -0.57936 -0.623061 -0.605074 -0.495662 -0.594589 -0.633074 -0.495662 -0.558002 -0.594118 -0.57936 -0.532203 -0.686352 -0.495662 -0.498338 -0.711322 -0.495662 -0.467673 -0.667551 -0.57936 -0.386691 -0.777682 -0.495662 -0.346401 -0.796445 -0.495662 -0.335996 -0.772521 -0.538812 -0.304757 -0.813291 -0.495662 -0.295602 -0.788861 -0.538812 -0.261892 -0.828089 -0.495662 -0.245777 -0.777133 -0.57936 -0.0349596 -0.867812 -0.495662 0.0116573 -0.868437 -0.495662 0.0113071 -0.84235 -0.538812 0.0582238 -0.866562 -0.495662 0.0564748 -0.840531 -0.538812 0.10454 -0.862201 -0.495662 0.1014 -0.836301 -0.538812 0.150408 -0.855393 -0.495662 0.14589 -0.829697 -0.538812 0.195638 -0.846194 -0.495662 0.1836 -0.794124 -0.57936 0.366723 -0.787295 -0.495662 0.40629 -0.767625 -0.495662 0.394085 -0.744566 -0.538812 0.444331 -0.74625 -0.495662 0.41699 -0.70033 -0.57936 0.483769 -0.65598 -0.57936 0.57967 -0.646763 -0.495662 0.562257 -0.627334 -0.538812 0.544001 -0.606964 -0.57936 0.571575 -0.581071 -0.57936 0.59744 -0.554444 -0.57936 0.686295 -0.532277 -0.495662 0.708459 -0.502399 -0.495662 0.687178 -0.487307 -0.538812 0.664865 -0.471484 -0.57936 0.764716 -0.411739 -0.495662 0.747621 -0.44202 -0.495662 0.782904 -0.432693 -0.447033 0.701617 -0.414821 -0.57936 0.717659 -0.386403 -0.57936 0.732217 -0.35805 -0.57936 0.745349 -0.329845 -0.57936 0.757115 -0.30186 -0.57936 0.76758 -0.27416 -0.57936 0.776808 -0.246803 -0.57936 0.784865 -0.219839 -0.57936 0.791817 -0.19331 -0.57936 0.829598 -0.146455 -0.538812 0.833751 -0.120588 -0.538812 0.806678 -0.116673 -0.57936 0.80266 -0.141699 -0.57936 0.813832 -0.0449353 -0.57936 0.862942 0.0982387 -0.495662 0.83702 0.0952877 -0.538812 0.865463 0.0727543 -0.495662 0.833751 0.120588 -0.538812 0.829598 0.146455 -0.538812 0.824499 0.172866 -0.538812 0.81839 0.199797 -0.538812 0.811206 0.227217 -0.538812 0.802878 0.255086 -0.538812 0.79334 0.283361 -0.538812 0.782524 0.31199 -0.538812 0.770363 0.340915 -0.538812 0.741744 0.399371 -0.538812 0.706991 0.458089 -0.538812 0.687178 0.487307 -0.538812 0.665679 0.516288 -0.538812 0.61749 0.573051 -0.538812 0.557721 0.699363 -0.447033 0.577116 0.683446 -0.447033 0.531998 0.653192 -0.538812 0.410566 0.794731 -0.447033 0.432694 0.782903 -0.447033 0.394085 0.744566 -0.538812 0.240048 0.834683 -0.495662 0.149836 0.881879 -0.447033 0.150408 0.855393 -0.495662 0.174511 0.877329 -0.447033 0.100154 0.888893 -0.447033 0.10454 0.862201 -0.495662 0.125044 0.885734 -0.447033 0.0501544 0.89311 -0.447033 0.0751835 0.891352 -0.447033 0.0564752 0.840531 -0.538812 -0.319006 0.835701 -0.447033 -0.304757 0.813291 -0.495662 -0.295442 0.844319 -0.447033 -0.365361 0.8165 -0.447033 -0.342318 0.826426 -0.447033 -0.335996 0.772521 -0.538812 -0.557724 0.69936 -0.447033 -0.53789 0.714728 -0.447033 -0.516216 0.665735 -0.538812 -0.650011 0.61453 -0.447033 -0.632521 0.632518 -0.447033 -0.604345 0.586898 -0.538812 -0.654286 0.530652 -0.538812 -0.697293 0.472721 -0.538812 -0.733649 0.414054 -0.538812 -0.763757 0.355467 -0.538812 -0.776616 0.32642 -0.538812 -0.798265 0.269176 -0.538812 -0.847019 0.192038 -0.495662 -0.821575 0.186269 -0.538812 -0.840175 0.220059 -0.495662 -0.827171 0.159594 -0.538812 -0.831789 0.133452 -0.538812 -0.835492 0.107866 -0.538812 -0.838342 0.0828548 -0.538812 -0.840397 0.0584315 -0.538812 -0.841715 0.0346056 -0.538812 -0.842349 0.0113837 -0.538812 -0.842349 -0.0113835 -0.538812 -0.841715 -0.0346058 -0.538812 -0.840397 -0.0584315 -0.538812 -0.838342 -0.0828548 -0.538812 -0.835492 -0.107866 -0.538812 -0.831789 -0.133452 -0.538812 -0.827171 -0.159594 -0.538812 -0.821575 -0.186269 -0.538812 -0.814937 -0.213448 -0.538812 -0.807189 -0.241098 -0.538812 -0.800667 -0.336529 -0.495662 -0.776616 -0.32642 -0.538812 -0.812503 -0.306853 -0.495662 -0.763757 -0.355467 -0.538812 -0.749456 -0.384705 -0.538812 -0.733649 -0.414054 -0.538812 -0.716279 -0.443425 -0.538812 -0.676641 -0.501835 -0.538812 -0.632517 -0.632521 -0.447033 -0.650009 -0.614532 -0.447033 -0.604345 -0.586898 -0.538812 -0.537888 -0.714729 -0.447033 -0.557721 -0.699363 -0.447033 -0.516216 -0.665735 -0.538812 -0.432694 -0.782903 -0.447033 -0.425507 -0.757141 -0.495662 -0.454482 -0.770459 -0.447033 -0.388116 -0.805933 -0.447033 -0.410566 -0.794731 -0.447033 -0.375075 -0.754321 -0.538812 -0.174511 -0.87733 -0.447033 -0.173114 -0.851088 -0.495662 -0.199048 -0.87209 -0.447033 -0.125044 -0.885734 -0.447033 -0.127542 -0.8591 -0.495662 -0.149836 -0.881879 -0.447033 -0.0751838 -0.891352 -0.447033 -0.0814259 -0.86469 -0.495662 -0.100154 -0.888893 -0.447033 -0.0250868 -0.894165 -0.447033 -0.0501546 -0.89311 -0.447033 -0.0339094 -0.841743 -0.538812 0.295442 -0.844319 -0.447033 0.283468 -0.820954 -0.495662 0.271645 -0.852274 -0.447033 0.342318 -0.826426 -0.447033 0.325741 -0.805116 -0.495662 0.319006 -0.835701 -0.447033 0.388118 -0.805932 -0.447033 0.365361 -0.8165 -0.447033 0.355707 -0.763645 -0.538812 0.53789 -0.714728 -0.447033 0.517632 -0.729533 -0.447033 0.500004 -0.677995 -0.538812 0.590758 -0.600572 -0.538812 0.714729 -0.537888 -0.447033 0.699363 -0.557721 -0.447033 0.665679 -0.516288 -0.538812 0.706991 -0.458089 -0.538812 0.725163 -0.428743 -0.538812 0.741744 -0.399371 -0.538812 0.756791 -0.370067 -0.538812 0.782524 -0.31199 -0.538812 0.79334 -0.283361 -0.538812 0.811205 -0.227217 -0.538812 0.81839 -0.199797 -0.538812 0.824499 -0.172866 -0.538812 0.841145 -0.0464434 -0.538812 0.865463 -0.0727543 -0.495662 0.888892 0.100156 -0.447033 0.859572 0.124323 -0.495662 0.85529 0.15099 -0.495662 0.850034 0.17822 -0.495662 0.843735 0.205985 -0.495662 0.836328 0.234253 -0.495662 0.806758 0.321653 -0.495662 0.805931 0.38812 -0.447033 0.782902 0.432696 -0.447033 0.728886 0.472275 -0.495662 0.708459 0.502399 -0.495662 0.650009 0.614532 -0.447033 0.57967 0.646763 -0.495662 0.517631 0.729534 -0.447033 0.444331 0.74625 -0.495662 0.388115 0.805933 -0.447033 0.365361 0.8165 -0.447033 0.319003 0.835702 -0.447033 0.271644 0.852274 -0.447033 0.195638 0.846194 -0.495662 8.14756e-08 0.894517 -0.447033 0.0250868 0.894165 -0.447033 -0.0501575 0.89311 -0.447033 -0.100155 0.888893 -0.447033 -0.149839 0.881878 -0.447033 -0.19905 0.87209 -0.447033 -0.261892 0.828089 -0.495662 -0.388118 0.805931 -0.447033 -0.410569 0.794729 -0.447033 -0.454483 0.770459 -0.447033 -0.498338 0.711322 -0.495662 -0.594589 0.633074 -0.495662 -0.699363 0.557721 -0.447033 -0.743766 0.496965 -0.447033 -0.782903 0.432693 -0.447033 -0.78741 0.366475 -0.495662 -0.826427 0.342314 -0.447033 -0.822986 0.277512 -0.495662 -0.832187 0.248564 -0.495662 -0.866165 0.223426 -0.447033 -0.852788 0.164536 -0.495662 -0.857549 0.137585 -0.495662 -0.861367 0.111207 -0.495662 -0.864305 0.0854207 -0.495662 -0.866424 0.060241 -0.495662 -0.867782 0.0356773 -0.495662 -0.868436 0.0117362 -0.495662 -0.868436 -0.011736 -0.495662 -0.867782 -0.0356775 -0.495662 -0.866424 -0.0602411 -0.495662 -0.864305 -0.0854208 -0.495662 -0.861367 -0.111207 -0.495662 -0.857549 -0.137585 -0.495662 -0.852788 -0.164536 -0.495662 -0.832187 -0.248564 -0.495662 -0.822986 -0.277512 -0.495662 -0.826425 -0.342319 -0.447033 -0.78741 -0.366475 -0.495662 -0.757408 -0.475915 -0.447033 -0.69936 -0.557725 -0.447033 -0.649711 -0.576364 -0.495662 -0.564297 -0.660218 -0.495662 -0.462751 -0.73497 -0.495662 -0.342316 -0.826427 -0.447033 -0.295439 -0.84432 -0.447033 -0.217956 -0.840723 -0.495662 -6.66203e-08 -0.894517 -0.447033 0.0250895 -0.894165 -0.447033 0.0751854 -0.891352 -0.447033 0.125047 -0.885734 -0.447033 0.174512 -0.877329 -0.447033 0.240048 -0.834683 -0.495662 0.432695 -0.782902 -0.447033 0.480756 -0.723321 -0.495662 0.577119 -0.683444 -0.447033 0.650011 -0.614529 -0.447033 0.662355 -0.561787 -0.495662 0.728886 -0.472275 -0.495662 0.805933 -0.388114 -0.447033 0.806758 -0.321653 -0.495662 0.844321 -0.295438 -0.447033 0.836328 -0.234254 -0.495662 0.843735 -0.205985 -0.495662 0.850034 -0.17822 -0.495662 0.85529 -0.15099 -0.495662 0.859571 -0.124323 -0.495662 0.862942 -0.0982386 -0.495662 0.888893 -0.100153 -0.447033 0.891352 0.0751875 -0.447033 0.885733 0.12505 -0.447033 0.881878 0.149842 -0.447033 0.877329 0.174513 -0.447033 0.872089 0.199052 -0.447033 0.866163 0.223434 -0.447033 0.859556 0.247638 -0.447033 0.852274 0.271645 -0.447033 0.8357 0.319008 -0.447033 0.826425 0.342319 -0.447033 0.8165 0.365361 -0.447033 0.794728 0.41057 -0.447033 0.770458 0.454483 -0.447033 0.757408 0.475915 -0.447033 0.743762 0.496969 -0.447033 0.729533 0.517632 -0.447033 0.683443 0.577119 -0.447033 0.66699 0.596059 -0.447033 0.632517 0.632521 -0.447033 0.61453 0.650011 -0.447033 0.596058 0.66699 -0.447033 0.537888 0.714729 -0.447033 0.496965 0.743765 -0.447033 0.47591 0.75741 -0.447033 0.454482 0.770459 -0.447033 0.342316 0.826427 -0.447033 0.29544 0.84432 -0.447033 0.247633 0.859558 -0.447033 0.223428 0.866165 -0.447033 0.199048 0.87209 -0.447033 -0.0250893 0.894165 -0.447033 -0.0751856 0.891352 -0.447033 -0.125047 0.885734 -0.447033 -0.174512 0.877329 -0.447033 -0.223431 0.866164 -0.447033 -0.247636 0.859557 -0.447033 -0.271645 0.852274 -0.447033 -0.432696 0.782902 -0.447033 -0.475913 0.757408 -0.447033 -0.496969 0.743763 -0.447033 -0.517632 0.729533 -0.447033 -0.577119 0.683443 -0.447033 -0.596059 0.66699 -0.447033 -0.614532 0.650009 -0.447033 -0.66699 0.596058 -0.447033 -0.683446 0.577116 -0.447033 -0.714729 0.537888 -0.447033 -0.729534 0.51763 -0.447033 -0.757411 0.47591 -0.447033 -0.770459 0.454482 -0.447033 -0.794731 0.410564 -0.447033 -0.805933 0.388114 -0.447033 -0.8165 0.365361 -0.447033 -0.835703 0.319001 -0.447033 -0.844321 0.295438 -0.447033 -0.852274 0.271643 -0.447033 -0.859558 0.247631 -0.447033 -0.87209 0.199047 -0.447033 -0.87733 0.174509 -0.447033 -0.881879 0.149833 -0.447033 -0.885735 0.125041 -0.447033 -0.888893 0.100154 -0.447033 -0.891352 0.0751808 -0.447033 -0.89311 0.0501503 -0.447033 -0.894166 0.0250842 -0.447033 -0.894517 8.14756e-08 -0.447033 -0.894165 -0.0250844 -0.447033 -0.89311 -0.0501622 -0.447033 -0.891352 -0.0751876 -0.447033 -0.888892 -0.100156 -0.447033 -0.885733 -0.12505 -0.447033 -0.881878 -0.149842 -0.447033 -0.877329 -0.174513 -0.447033 -0.872089 -0.199052 -0.447033 -0.859556 -0.247638 -0.447033 -0.852274 -0.271645 -0.447033 -0.844319 -0.295444 -0.447033 -0.8357 -0.319008 -0.447033 -0.8165 -0.365361 -0.447033 -0.805931 -0.38812 -0.447033 -0.794728 -0.41057 -0.447033 -0.770458 -0.454483 -0.447033 -0.743762 -0.496969 -0.447033 -0.729533 -0.517632 -0.447033 -0.714728 -0.53789 -0.447033 -0.683443 -0.577119 -0.447033 -0.666989 -0.596059 -0.447033 -0.614529 -0.650011 -0.447033 -0.596058 -0.66699 -0.447033 -0.577116 -0.683446 -0.447033 -0.517631 -0.729534 -0.447033 -0.496965 -0.743765 -0.447033 -0.475911 -0.75741 -0.447033 -0.365361 -0.8165 -0.447033 -0.319003 -0.835702 -0.447033 -0.271644 -0.852274 -0.447033 -0.247633 -0.859558 -0.447033 -0.223428 -0.866165 -0.447033 0.0501577 -0.89311 -0.447033 0.100155 -0.888893 -0.447033 0.149839 -0.881878 -0.447033 0.19905 -0.87209 -0.447033 0.223431 -0.866164 -0.447033 0.247635 -0.859557 -0.447033 0.410569 -0.794729 -0.447033 0.454483 -0.770459 -0.447033 0.475914 -0.757408 -0.447033 0.496969 -0.743763 -0.447033 0.557724 -0.69936 -0.447033 0.596059 -0.66699 -0.447033 0.614532 -0.650009 -0.447033 0.632521 -0.632518 -0.447033 0.66699 -0.596058 -0.447033 0.683446 -0.577116 -0.447033 0.729534 -0.517631 -0.447033 0.743765 -0.496965 -0.447033 0.757411 -0.47591 -0.447033 0.770459 -0.454482 -0.447033 0.794731 -0.410564 -0.447033 0.8165 -0.365361 -0.447033 0.826427 -0.342314 -0.447033 0.835703 -0.319001 -0.447033 0.852274 -0.271643 -0.447033 0.859558 -0.24763 -0.447033 0.866165 -0.223426 -0.447033 0.87209 -0.199047 -0.447033 0.87733 -0.174509 -0.447033 0.881879 -0.149832 -0.447033 0.885735 -0.125041 -0.447033 0.891352 -0.0751809 -0.447033 0.89311 -0.0501506 -0.447033 0.894166 -0.0250843 -0.447033 -0.998427 0.0560703 0 -0.999607 0.0280461 0 -0.998427 0.0560708 0 -1 -1.74846e-07 -0 -0.999607 0.0280466 0 -1 3.01992e-07 0 -0.993712 0.111964 0 -0.990181 0.13979 0 -0.990181 0.13979 0 -0.993712 0.111965 0 -0.996462 0.0840504 0 -0.996462 0.0840504 0 -0.974928 0.222521 0 -0.980785 0.19509 0 -0.974928 0.222521 0 -0.980785 0.19509 0 -0.985871 0.167506 0 -0.985871 0.167506 0 -0.952775 0.303677 0 -0.952775 0.303677 0 -0.960917 0.276835 0 -0.968304 0.249776 0 -0.960917 0.276835 0 -0.968304 0.249776 0 -0.934249 0.356622 0 -0.92388 0.382683 0 -0.92388 0.382683 0 -0.943883 0.330279 0 -0.943883 0.330279 0 -0.934249 0.356622 0 -0.888446 0.458982 0 -0.900969 0.433884 0 -0.888446 0.458982 0 -0.900969 0.433884 0 -0.912783 0.408444 0 -0.912783 0.408444 0 -0.846724 0.532032 0 -0.846724 0.532032 0 -0.861313 0.508075 0 -0.875223 0.483719 0 -0.861313 0.508075 0 -0.875223 0.483719 0 -0.815561 0.578671 0 -0.79901 0.601317 0 -0.79901 0.601317 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.815561 0.578671 0 -0.745642 0.666347 0 -0.764037 0.645172 0 -0.745642 0.666346 0 -0.764037 0.645172 0 -0.781831 0.62349 0 -0.781831 0.62349 0 -0.686997 0.72666 0 -0.686997 0.72666 0 -0.707107 0.707107 0 -0.72666 0.686997 0 -0.707107 0.707107 0 -0.72666 0.686997 0 -0.645172 0.764037 0 -0.62349 0.781831 0 -0.62349 0.781832 0 -0.666346 0.745642 0 -0.666346 0.745642 0 -0.645172 0.764037 0 -0.55557 0.831469 0 -0.578671 0.815561 0 -0.55557 0.83147 0 -0.578672 0.815561 0 -0.601317 0.799011 0 -0.601317 0.79901 0 -0.483719 0.875224 0 -0.483719 0.875223 0 -0.508075 0.861313 0 -0.532032 0.846724 0 -0.508075 0.861313 0 -0.532032 0.846724 0 -0.433884 0.900969 0 -0.408444 0.912783 0 -0.408444 0.912783 0 -0.458982 0.888446 0 -0.458982 0.888446 0 -0.433883 0.900969 0 -0.330279 0.943883 0 -0.356622 0.934249 0 -0.330279 0.943883 0 -0.356621 0.934249 0 -0.382684 0.923879 0 -0.382684 0.923879 0 -0.249777 0.968304 0 -0.249777 0.968304 0 -0.276836 0.960917 0 -0.303677 0.952775 0 -0.276835 0.960917 0 -0.303677 0.952775 0 -0.19509 0.980785 0 -0.167506 0.985871 0 -0.167506 0.985871 0 -0.222521 0.974928 0 -0.222521 0.974928 0 -0.19509 0.980785 0 -0.0840506 0.996462 0 -0.111965 0.993712 0 -0.0840506 0.996462 0 -0.111965 0.993712 0 -0.13979 0.990181 0 -0.13979 0.990181 0 -1.19249e-08 1 0 -1.19249e-08 1 0 -0.0280463 0.999607 0 -0.0560705 0.998427 0 -0.0280463 0.999607 0 -0.0560705 0.998427 0 0.0560705 0.998427 0 0.0840505 0.996462 0 0.0840505 0.996462 0 0.0280463 0.999607 0 0.0280463 0.999607 0 0.0560705 0.998427 0 0.167506 0.985871 0 0.13979 0.990181 0 0.167506 0.985871 0 0.13979 0.990181 0 0.111965 0.993712 0 0.111965 0.993712 0 0.249777 0.968304 0 0.249777 0.968304 0 0.222521 0.974928 0 0.19509 0.980785 0 0.222521 0.974928 0 0.19509 0.980785 0 0.303677 0.952775 0 0.330279 0.943883 0 0.330279 0.943883 0 0.276836 0.960917 0 0.276836 0.960917 0 0.303677 0.952775 0 0.408444 0.912783 0 0.382684 0.92388 0 0.408444 0.912783 0 0.382683 0.92388 0 0.356622 0.934249 0 0.356622 0.934249 0 0.483719 0.875224 0 0.483719 0.875223 0 0.458982 0.888446 0 0.433884 0.900969 0 0.458982 0.888446 0 0.433884 0.900969 0 0.532032 0.846724 0 0.55557 0.831469 0 0.55557 0.83147 0 0.508076 0.861313 0 0.508075 0.861313 0 0.532032 0.846724 0 0.62349 0.781832 0 0.601317 0.79901 0 0.62349 0.781831 0 0.601317 0.799011 0 0.578672 0.815561 0 0.578671 0.815561 0 0.686997 0.72666 0 0.686997 0.72666 0 0.666346 0.745642 0 0.645172 0.764037 0 0.666347 0.745642 0 0.645172 0.764037 0 0.72666 0.686997 0 0.745642 0.666346 0 0.745642 0.666346 0 0.707107 0.707107 0 0.707107 0.707107 0 0.72666 0.686997 0 0.799011 0.601317 0 0.781831 0.62349 0 0.79901 0.601317 0 0.781832 0.62349 0 0.764037 0.645172 0 0.764037 0.645172 0 0.846724 0.532032 0 0.846724 0.532032 0 0.83147 0.55557 0 0.815561 0.578671 0 0.83147 0.55557 0 0.815561 0.578671 0 0.875223 0.483719 0 0.888446 0.458982 0 0.888446 0.458982 0 0.861313 0.508075 0 0.861313 0.508075 0 0.875223 0.483719 0 0.923879 0.382684 0 0.912783 0.408444 0 0.92388 0.382683 0 0.912783 0.408444 0 0.900969 0.433884 0 0.900969 0.433884 0 0.952775 0.303677 0 0.952775 0.303677 0 0.943883 0.330279 0 0.934249 0.356622 0 0.943883 0.330279 0 0.934249 0.356622 0 0.968304 0.249777 0 0.974928 0.222521 0 0.974928 0.222521 0 0.960917 0.276835 0 0.960917 0.276835 0 0.968304 0.249776 0 0.990181 0.13979 0 0.985871 0.167506 0 0.990181 0.13979 0 0.985871 0.167506 0 0.980785 0.19509 0 0.980785 0.19509 0 0.998427 0.0560706 0 0.998427 0.0560703 0 0.996462 0.0840506 0 0.993712 0.111964 0 0.996462 0.0840504 0 0.993712 0.111965 0 1 8.74228e-08 0 0.999607 -0.0280464 0 0.999607 -0.0280462 0 0.999607 0.0280464 0 0.999607 0.0280461 0 1 8.74228e-08 0 0.993712 -0.111964 0 0.996462 -0.0840505 0 0.993712 -0.111964 0 0.996461 -0.0840507 0 0.998427 -0.0560704 0 0.998427 -0.0560704 0 0.980785 -0.19509 0 0.980785 -0.19509 0 0.985871 -0.167506 0 0.990181 -0.13979 0 0.985871 -0.167506 0 0.990181 -0.13979 0 0.968304 -0.249776 0 0.960917 -0.276836 0 0.960917 -0.276836 0 0.974928 -0.222521 0 0.974928 -0.222521 0 0.968304 -0.249776 0 0.934249 -0.356622 0 0.943883 -0.330279 0 0.934249 -0.356621 0 0.943883 -0.330279 0 0.952775 -0.303677 0 0.952775 -0.303677 0 0.900969 -0.433884 0 0.900969 -0.433884 0 0.912783 -0.408444 0 0.92388 -0.382683 0 0.912783 -0.408444 0 0.92388 -0.382683 0 0.875223 -0.483719 0 0.861313 -0.508075 0 0.861313 -0.508075 0 0.888446 -0.458982 0 0.888446 -0.458982 0 0.875223 -0.483719 0 0.815561 -0.578671 0 0.83147 -0.55557 0 0.815561 -0.578671 0 0.83147 -0.55557 0 0.846724 -0.532032 0 0.846724 -0.532032 0 0.764037 -0.645172 0 0.764037 -0.645172 0 0.781832 -0.62349 0 0.799011 -0.601317 0 0.781831 -0.62349 0 0.799011 -0.601317 0 0.72666 -0.686997 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.745642 -0.666347 0 0.745642 -0.666347 0 0.72666 -0.686997 0 0.645172 -0.764037 0 0.666347 -0.745642 0 0.645172 -0.764037 0 0.666347 -0.745642 0 0.686997 -0.72666 0 0.686997 -0.72666 0 0.578671 -0.815561 0 0.578671 -0.815561 0 0.601317 -0.799011 0 0.62349 -0.781832 0 0.601317 -0.799011 0 0.62349 -0.781832 0 0.532032 -0.846724 0 0.508075 -0.861313 0 0.508075 -0.861313 0 0.55557 -0.83147 0 0.55557 -0.83147 0 0.532032 -0.846724 0 0.433884 -0.900969 0 0.458982 -0.888446 0 0.433884 -0.900969 0 0.458982 -0.888446 0 0.483719 -0.875223 0 0.483719 -0.875223 0 0.356622 -0.934249 0 0.356622 -0.934249 0 0.382683 -0.92388 0 0.408444 -0.912783 0 0.382683 -0.92388 0 0.408444 -0.912783 0 0.303677 -0.952775 0 0.276836 -0.960917 0 0.276836 -0.960917 0 0.330279 -0.943883 0 0.330279 -0.943883 0 0.303677 -0.952775 0 0.19509 -0.980785 0 0.222521 -0.974928 0 0.19509 -0.980785 0 0.222521 -0.974928 0 0.249776 -0.968304 0 0.249776 -0.968304 0 0.111964 -0.993712 0 0.111964 -0.993712 0 0.13979 -0.990181 0 0.167506 -0.985871 0 0.13979 -0.990181 0 0.167506 -0.985871 0 0.0560704 -0.998427 0 0.0280463 -0.999607 0 0.0280463 -0.999607 0 0.0840505 -0.996462 0 0.0840506 -0.996462 0 0.0560704 -0.998427 0 4.37114e-08 -1 0 -0.0280462 -0.999607 -0 -0.0280462 -0.999607 -0 -7.54979e-08 -1 -0 -0.0560704 -0.998427 -0 -0.0560704 -0.998427 -0 -0.0840505 -0.996462 -0 -0.0840505 -0.996462 -0 -0.111964 -0.993712 -0 -0.111964 -0.993712 -0 -0.13979 -0.990181 -0 -0.13979 -0.990181 -0 -0.167506 -0.985871 -0 -0.167506 -0.985871 -0 -0.19509 -0.980785 -0 -0.19509 -0.980785 -0 -0.222521 -0.974928 -0 -0.222521 -0.974928 -0 -0.249777 -0.968304 -0 -0.249776 -0.968304 -0 -0.276835 -0.960917 -0 -0.276835 -0.960917 -0 -0.303677 -0.952775 -0 -0.303677 -0.952775 -0 -0.330279 -0.943883 -0 -0.330279 -0.943883 -0 -0.356622 -0.934249 -0 -0.356622 -0.934249 -0 -0.382683 -0.92388 -0 -0.382683 -0.92388 -0 -0.408444 -0.912783 -0 -0.408444 -0.912783 -0 -0.433884 -0.900969 -0 -0.433884 -0.900969 -0 -0.458982 -0.888446 -0 -0.458982 -0.888446 -0 -0.483719 -0.875223 -0 -0.483719 -0.875223 -0 -0.508075 -0.861313 -0 -0.508075 -0.861313 -0 -0.532032 -0.846724 -0 -0.532032 -0.846724 -0 -0.55557 -0.83147 -0 -0.55557 -0.83147 -0 -0.578671 -0.815561 -0 -0.578671 -0.815561 -0 -0.601317 -0.799011 -0 -0.601317 -0.79901 -0 -0.62349 -0.781832 -0 -0.62349 -0.781832 -0 -0.645172 -0.764037 -0 -0.645172 -0.764037 -0 -0.666347 -0.745642 -0 -0.666347 -0.745642 -0 -0.686997 -0.72666 -0 -0.686997 -0.72666 -0 -0.707107 -0.707107 -0 -0.707107 -0.707107 -0 -0.72666 -0.686997 -0 -0.72666 -0.686997 -0 -0.745642 -0.666347 -0 -0.745642 -0.666347 -0 -0.764037 -0.645172 -0 -0.764037 -0.645172 -0 -0.781831 -0.62349 -0 -0.781831 -0.62349 -0 -0.799011 -0.601317 -0 -0.79901 -0.601317 -0 -0.815561 -0.578671 -0 -0.815561 -0.578671 -0 -0.83147 -0.55557 -0 -0.83147 -0.55557 -0 -0.846724 -0.532032 -0 -0.846724 -0.532032 -0 -0.861313 -0.508075 -0 -0.861313 -0.508075 -0 -0.875223 -0.483719 -0 -0.875223 -0.483719 -0 -0.888446 -0.458982 -0 -0.888446 -0.458982 -0 -0.900969 -0.433884 -0 -0.900969 -0.433884 -0 -0.912783 -0.408444 -0 -0.912783 -0.408444 -0 -0.92388 -0.382683 -0 -0.92388 -0.382683 -0 -0.934249 -0.356622 -0 -0.934249 -0.356622 -0 -0.943883 -0.330279 -0 -0.943883 -0.330279 -0 -0.952775 -0.303677 -0 -0.952775 -0.303677 -0 -0.960917 -0.276836 -0 -0.960917 -0.276836 -0 -0.968304 -0.249776 -0 -0.968304 -0.249776 -0 -0.974928 -0.222521 -0 -0.974928 -0.222521 -0 -0.980785 -0.19509 -0 -0.980785 -0.19509 -0 -0.985871 -0.167506 -0 -0.985871 -0.167506 -0 -0.990181 -0.13979 -0 -0.990181 -0.13979 -0 -0.993712 -0.111964 -0 -0.993712 -0.111964 -0 -0.996462 -0.0840505 -0 -0.996462 -0.0840505 -0 -0.998427 -0.0560704 -0 -0.998427 -0.0560705 -0 -0.999607 -0.0280463 -0 -0.999607 -0.0280463 -0 - - - - - - - - - - - - - - -

0 1 2 3 4 5 6 7 8 9 10 11 12 8 7 3 5 13 14 15 16 8 12 17 18 3 19 20 21 22 3 13 19 23 18 24 25 26 27 4 28 5 24 29 23 29 25 23 30 31 32 33 34 35 36 33 37 38 39 40 37 33 35 34 25 27 35 34 27 25 29 26 41 36 42 33 36 41 39 42 40 41 42 39 43 39 38 31 30 43 44 45 30 31 43 38 44 30 32 46 17 45 45 17 12 45 44 46 47 7 6 48 49 50 18 19 24 51 52 53 54 55 56 52 57 58 59 60 61 62 63 58 64 65 66 67 68 69 65 70 71 72 73 74 75 76 74 77 78 79 80 81 82 79 83 73 61 76 84 85 86 62 59 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 103 106 107 108 109 110 105 101 111 112 113 114 115 116 117 118 119 120 121 122 116 123 124 125 126 127 117 128 129 130 131 124 132 133 119 134 112 135 136 137 135 132 138 139 140 141 142 143 144 145 146 147 136 148 149 142 150 151 152 153 143 152 142 154 155 156 157 158 159 160 161 159 145 162 163 164 165 163 166 167 168 169 170 166 162 171 172 173 174 175 170 176 173 177 178 179 171 180 181 182 183 184 185 178 186 187 188 189 47 190 191 192 193 194 195 196 194 197 198 199 200 201 202 191 203 204 205 206 195 207 208 209 210 203 210 211 212 213 214 212 215 216 217 184 201 218 219 220 221 222 223 224 225 222 222 225 226 227 225 228 229 230 231 7 47 189 232 28 4 233 232 234 188 235 189 234 236 233 233 28 232 235 49 48 58 85 62 48 189 235 237 236 234 238 237 234 238 239 237 240 239 241 55 48 50 239 238 241 55 50 56 242 243 53 55 54 242 243 242 54 244 240 245 241 245 240 246 247 244 244 245 246 243 248 53 249 247 250 248 251 53 247 246 250 252 253 254 255 53 251 256 64 77 255 257 51 246 245 258 259 255 251 260 249 261 262 255 259 261 263 260 260 263 264 262 265 255 263 266 264 257 265 267 268 265 269 262 269 265 270 265 268 266 263 271 272 270 268 271 273 274 275 270 272 276 274 277 278 270 275 279 280 278 281 278 282 278 275 282 278 281 283 279 283 284 283 285 286 281 285 283 286 287 283 287 288 284 289 290 287 289 287 286 291 287 290 292 288 291 293 294 291 291 290 293 294 293 295 292 294 296 297 294 298 295 298 294 298 299 297 297 300 296 301 297 299 300 302 303 297 301 302 304 305 302 304 302 301 306 307 303 305 306 302 308 306 309 306 305 309 310 307 311 311 306 308 308 312 311 313 311 312 314 315 313 311 313 315 316 317 310 315 314 318 319 318 320 318 319 315 321 322 323 320 324 319 324 325 322 322 319 324 326 327 323 328 322 325 329 326 328 322 328 326 330 327 331 331 326 329 331 332 333 329 332 331 330 334 335 331 333 334 336 337 334 336 334 333 338 337 339 337 338 334 340 338 341 339 341 338 342 0 340 343 344 335 0 342 345 340 341 342 1 0 345 346 347 0 346 2 348 2 1 349 350 2 349 351 2 350 350 352 351 352 353 351 354 348 355 353 352 356 357 353 356 358 353 357 358 359 360 357 361 358 362 358 361 362 361 363 364 362 363 365 362 364 365 366 367 364 368 365 369 365 368 369 368 370 369 371 372 371 369 370 366 373 374 371 375 372 376 372 375 376 375 377 376 378 379 378 376 377 380 381 382 378 383 379 384 379 383 384 383 385 385 386 384 387 386 385 386 388 389 387 390 386 391 386 390 391 390 392 392 393 391 394 393 392 395 396 394 393 394 396 397 396 398 399 396 395 395 400 399 401 399 400 399 401 402 401 403 402 404 402 403 404 403 405 406 405 407 405 406 404 408 409 407 406 407 409 408 410 411 411 409 408 412 413 414 410 415 411 415 410 416 415 416 417 418 417 416 419 417 418 418 420 419 420 421 419 421 420 15 421 15 14 422 14 16 423 424 425 426 422 16 427 428 429 425 424 430 431 432 433 427 434 428 435 436 437 438 439 440 441 442 443 436 444 443 445 446 447 448 449 450 451 452 453 445 454 452 455 456 457 458 459 460 461 462 463 464 463 465 466 467 468 462 469 470 471 472 473 474 473 475 476 477 478 479 480 478 481 482 483 484 485 486 487 488 489 488 483 490 491 492 493 494 495 493 496 497 498 496 499 492 500 501 502 501 503 504 505 506 507 508 509 500 510 511 512 513 512 506 514 515 516 511 517 516 518 519 520 519 521 522 523 524 525 518 520 526 527 528 529 530 528 523 531 532 533 532 11 534 535 536 537 538 9 532 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 547 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 570 527 571 572 573 574 569 575 574 576 577 578 573 572 578 579 580 581 577 576 581 582 583 584 583 580 579 582 585 586 586 583 582 587 588 585 589 590 588 589 591 592 593 589 588 592 594 595 596 597 598 599 595 600 594 601 595 602 603 600 601 600 595 604 605 606 603 607 608 609 610 611 610 609 608 612 613 614 610 613 611 615 612 616 617 618 619 615 616 620 615 620 621 622 623 624 625 621 620 626 627 628 627 621 625 628 629 626 626 630 627 631 632 633 629 631 626 634 633 632 635 636 637 634 638 639 639 633 634 639 638 640 641 642 643 644 645 640 639 640 645 644 277 646 644 646 645 277 647 646 648 646 647 632 631 629 616 612 614 625 628 627 608 609 603 613 612 611 602 600 601 603 602 607 592 591 649 594 592 649 587 593 588 589 593 591 650 651 652 586 585 588 581 580 577 579 584 583 573 578 577 653 580 654 655 656 573 573 569 574 570 571 568 568 575 569 657 563 658 657 9 564 659 660 661 662 543 660 663 664 665 666 556 667 668 665 669 670 667 671 672 673 674 675 665 676 677 678 679 678 674 552 675 553 669 545 680 677 681 549 682 683 684 681 671 685 664 686 687 683 688 689 690 548 691 692 693 694 695 696 691 697 567 698 557 699 700 701 702 693 696 703 693 704 661 705 698 704 706 707 659 698 708 709 710 707 711 712 709 713 714 542 715 716 717 712 718 719 717 720 721 722 723 724 725 726 727 728 725 729 730 731 732 733 734 735 736 737 738 737 739 740 741 742 743 736 744 743 745 746 747 741 748 742 749 750 751 752 746 753 754 755 756 757 758 759 760 523 518 761 740 733 223 756 759 720 726 762 537 713 544 763 718 715 764 765 544 507 509 505 658 766 767 766 563 535 533 534 570 524 527 534 527 529 571 760 530 523 523 528 527 525 521 518 526 760 518 768 769 487 519 515 770 519 770 520 515 511 516 515 514 770 771 772 773 511 510 517 774 515 522 512 507 506 510 512 513 775 507 773 500 509 507 500 775 503 500 502 508 776 777 501 501 777 502 498 776 501 498 504 778 776 498 497 492 499 493 496 498 499 778 494 499 487 769 493 769 491 493 489 768 487 488 779 489 487 495 780 488 780 781 779 488 490 471 473 474 483 486 481 490 483 482 485 481 486 782 783 784 484 477 476 477 484 486 784 785 477 479 472 480 477 479 478 473 472 479 786 479 785 473 786 787 788 469 789 474 475 790 790 468 467 468 790 475 468 462 466 791 466 462 463 792 461 791 462 461 451 793 794 464 792 463 795 463 470 796 456 455 464 465 796 456 796 465 457 797 798 456 799 800 798 797 793 456 797 457 793 797 794 801 802 803 451 794 452 452 454 453 804 447 446 445 447 454 448 804 446 449 448 446 805 449 806 807 450 449 449 442 807 808 809 443 441 807 442 435 444 436 443 444 441 439 438 810 810 437 436 439 431 440 437 810 438 431 433 440 811 431 812 813 432 431 813 814 432 814 813 434 427 814 434 815 429 428 816 422 426 429 815 817 815 430 817 424 423 818 430 815 425 816 818 423 818 816 426 819 820 648 821 822 823 646 648 820 819 824 820 820 825 645 826 827 633 826 639 825 827 828 631 633 639 826 829 830 831 631 633 827 623 621 627 631 828 626 622 615 621 828 630 626 612 832 617 623 627 630 617 833 611 623 622 621 609 833 605 832 615 622 605 834 603 612 615 832 835 836 837 612 617 611 597 592 595 611 833 609 589 592 596 609 605 603 838 839 840 834 600 603 586 588 650 600 834 599 652 654 583 597 595 599 841 842 843 592 597 596 653 655 577 589 596 590 844 845 655 588 590 650 656 533 569 650 652 586 11 846 524 583 586 652 846 847 525 583 654 580 847 848 521 580 653 577 848 849 522 573 577 655 850 851 771 573 656 569 852 511 774 569 533 570 773 512 852 534 527 570 775 772 853 523 527 524 853 854 503 518 523 525 854 855 504 519 518 521 855 856 778 515 519 522 856 857 494 511 515 774 857 858 495 512 511 852 858 859 780 507 512 773 860 861 782 500 507 775 862 483 781 500 503 501 784 486 862 498 501 504 783 863 785 499 498 778 863 864 786 493 499 494 787 864 865 487 493 495 787 866 475 488 487 780 866 469 468 781 483 488 470 788 867 862 486 483 868 869 870 784 477 486 795 799 465 785 479 477 800 868 871 786 473 479 800 872 797 787 475 473 458 794 872 475 866 468 458 873 452 469 462 468 801 445 873 462 470 463 801 806 446 465 463 795 805 874 875 465 799 456 805 808 442 797 456 800 876 877 878 794 797 872 879 436 809 452 794 458 879 880 810 873 445 452 880 812 439 801 446 445 811 881 882 806 449 446 883 813 811 805 442 449 883 884 434 808 443 442 884 885 428 443 809 436 885 886 815 436 879 810 886 887 425 810 880 439 887 888 423 431 439 812 888 889 816 813 431 811 889 890 422 434 813 883 890 891 14 428 434 884 891 892 421 815 428 885 892 893 419 425 815 886 893 894 417 423 425 887 894 895 415 816 423 888 895 896 411 816 889 422 414 409 896 422 890 14 897 406 414 14 891 421 898 404 897 421 892 419 898 899 402 419 893 417 899 398 399 417 894 415 397 900 901 415 895 411 902 393 397 411 896 409 902 388 391 409 414 406 389 903 904 897 404 406 389 905 384 898 402 404 905 906 379 399 402 899 380 376 906 398 396 399 380 907 372 393 396 397 366 369 907 391 393 902 908 909 910 391 388 386 367 359 362 384 386 389 360 908 911 384 905 379 360 912 353 379 906 376 912 348 351 376 380 372 346 354 913 372 907 369 347 913 914 366 365 369 347 915 340 367 362 365 335 338 915 359 358 362 344 916 330 360 353 358 916 917 327 912 351 353 917 918 323 2 351 348 919 920 316 0 2 346 921 319 321 340 0 347 310 315 921 915 338 340 307 317 922 334 338 335 922 923 303 331 334 330 923 924 300 326 331 327 924 925 296 322 326 323 925 926 292 319 322 321 926 927 288 315 319 921 927 928 284 311 315 310 928 929 279 306 311 307 930 931 932 306 303 302 267 270 280 297 302 300 932 933 257 294 297 296 933 57 51 292 291 294 242 52 63 291 288 287 55 63 934 283 287 284 48 934 935 279 278 283 936 189 935 280 270 278 937 7 936 267 265 270 12 937 938 257 255 265 52 58 63 255 51 53 45 939 30 52 242 53 30 940 43 55 242 63 941 39 43 48 55 934 942 41 39 935 189 48 943 33 41 936 7 189 944 34 33 7 937 12 940 945 946 45 938 939 947 25 948 940 30 939 949 23 947 941 43 940 950 18 949 942 39 941 951 3 950 942 943 41 4 951 952 943 944 33 949 947 953 34 948 25 954 234 232 25 947 23 955 238 234 18 23 949 956 241 238 3 18 950 957 245 241 4 3 951 958 955 959 954 232 952 960 246 258 954 955 234 961 250 960 955 956 238 962 261 961 956 957 241 961 960 963 964 271 263 250 261 249 250 246 960 965 274 273 261 250 961 266 271 276 962 964 263 274 648 647 277 274 647 276 271 274 646 820 645 966 824 819 966 641 824 645 825 639 824 967 825 827 968 636 968 826 967 636 969 828 827 826 968 623 630 970 828 827 636 971 972 973 828 969 630 832 622 974 969 970 630 975 976 977 970 624 623 833 619 606 624 974 622 978 979 980 618 832 974 604 835 834 832 618 617 981 597 599 833 617 619 982 983 984 833 606 605 590 596 839 604 834 605 650 590 838 835 599 834 985 986 987 981 599 835 654 988 841 597 981 598 653 841 844 596 598 839 989 990 991 590 839 838 845 531 656 650 838 651 992 538 531 651 988 652 846 10 993 654 652 988 993 994 847 653 654 841 994 995 848 844 655 653 996 997 850 655 845 656 998 774 849 656 531 533 771 852 998 532 534 533 772 851 999 11 524 534 853 999 1000 525 524 846 854 1000 1001 521 525 847 1001 1002 855 522 521 848 1002 1003 856 774 522 849 1003 1004 857 852 774 998 1004 1005 858 773 852 771 1006 1007 860 775 773 772 1008 781 859 503 775 853 782 862 1008 504 503 854 783 861 1009 778 504 855 863 1009 1010 494 778 856 1010 1011 864 495 494 857 1012 1013 1014 780 495 858 789 866 865 859 781 780 788 1014 1015 1008 862 781 1015 1016 867 782 784 862 1017 795 867 783 785 784 868 799 1017 863 786 785 870 1018 871 864 787 786 459 872 871 787 865 866 460 1019 1020 866 789 469 802 873 460 469 788 470 803 1021 1022 470 867 795 874 806 803 799 795 1017 875 1023 1024 799 868 800 1025 808 875 872 800 871 1026 809 1025 458 872 459 876 879 1026 873 458 460 1027 880 876 802 801 873 881 812 1027 803 806 801 1028 1029 1030 874 805 806 1031 883 882 875 808 805 1032 884 1031 1025 809 808 1033 885 1032 809 1026 879 1034 886 1033 879 876 880 1035 887 1034 880 1027 812 1036 888 1035 811 812 881 1037 889 1036 883 811 882 1038 890 1037 884 883 1031 1039 891 1038 885 884 1032 1040 892 1039 886 885 1033 1041 893 1040 887 886 1034 1042 894 1041 888 887 1035 1043 895 1042 889 888 1036 1043 412 896 890 889 1037 1044 1045 1046 890 1038 891 1047 897 413 891 1039 892 1048 898 1047 892 1040 893 1049 899 1048 893 1041 894 900 398 1049 894 1042 895 1050 1051 1052 895 1043 896 1053 902 901 896 412 414 903 388 1053 414 413 897 1054 1055 1056 1047 898 897 1057 905 904 1048 899 898 381 906 1057 1049 398 899 382 1058 1059 900 397 398 373 907 382 901 902 397 374 1060 1061 388 902 1053 1062 367 374 388 903 389 908 359 1062 905 389 904 910 1063 911 905 1057 906 355 912 911 380 906 381 354 1064 1065 380 382 907 1065 1066 913 907 373 366 1067 1068 1069 374 367 366 343 915 914 367 1062 359 344 1069 1070 908 360 359 1070 1071 916 911 912 360 1071 1072 917 355 348 912 1072 1073 918 346 348 354 1074 321 918 347 346 913 316 921 1074 914 915 347 317 920 1075 343 335 915 922 1075 1076 330 335 344 923 1076 1077 327 330 916 1077 1078 924 323 327 917 1078 1079 925 321 323 918 1079 1080 926 921 321 1074 1080 1081 927 310 921 316 1081 1082 928 307 310 317 1083 1084 930 303 307 922 1085 280 929 303 923 300 932 267 1085 296 300 924 933 931 1086 292 296 925 1086 1087 57 288 292 926 1087 85 58 284 288 927 1088 934 62 284 928 279 935 1088 1089 280 279 929 936 1089 1090 1085 267 280 1091 937 1090 267 932 257 1092 938 1091 933 51 257 1093 1094 1095 57 52 51 939 945 940 946 941 940 45 12 938 62 934 63 941 1096 942 1088 935 934 942 1097 943 936 935 1089 1098 944 943 1090 937 936 944 1099 948 1091 938 937 21 946 1100 939 1092 945 953 947 1101 949 953 1102 948 34 944 1096 941 946 950 1102 1103 1097 942 1096 1104 951 1103 1098 943 1097 1105 952 1104 1098 1099 944 1106 1102 953 948 1101 947 954 959 955 958 956 955 952 232 4 949 1102 950 956 1107 957 951 950 1103 957 1108 258 952 951 1104 1109 958 1110 959 954 1105 963 960 1111 961 963 1112 957 258 245 958 1107 956 1113 962 1112 1107 1108 957 1114 273 964 258 1111 960 1114 1115 1116 1117 965 1118 261 962 263 962 961 1112 1114 964 1113 965 648 274 271 964 273 965 273 1118 819 648 965 820 824 825 642 641 966 1119 1120 1121 825 967 826 641 1122 967 1123 1124 1125 1122 637 968 635 831 969 636 968 637 1126 624 970 636 635 969 974 624 1127 969 831 970 618 974 976 831 1126 970 619 975 1128 1126 1127 624 606 1128 979 976 974 1127 979 836 604 975 618 976 1129 1130 1131 619 618 975 983 598 981 619 1128 606 839 598 982 606 979 604 1132 1133 1134 836 835 604 651 838 985 837 981 835 988 651 987 983 981 837 1135 842 987 598 983 982 844 843 989 839 982 840 989 992 845 838 840 985 1136 1137 562 985 987 651 10 657 1138 842 988 987 993 1138 1139 841 988 842 1139 1140 994 841 843 844 1141 1142 996 989 845 844 1143 849 995 992 531 845 850 998 1143 538 532 531 851 997 1144 9 11 532 999 1144 1145 10 846 11 1000 1145 1146 847 846 993 1001 1146 1147 848 847 994 1147 1148 1002 849 848 995 1148 1149 1003 998 849 1143 1149 1150 1004 771 998 850 1151 1152 1006 772 771 851 1153 859 1005 853 772 999 860 1008 1153 1000 854 853 861 1007 1154 855 854 1001 1009 1154 1155 856 855 1002 1010 1155 1156 857 856 1003 1156 1157 1011 858 857 1004 1158 865 1011 859 858 1005 1014 789 1158 1153 1008 859 1015 1013 1159 860 782 1008 1159 1160 1016 861 783 782 869 1017 1016 783 1009 863 870 1161 1162 1010 864 863 1162 1163 1018 1011 865 864 1019 459 1018 865 1158 789 1020 1164 1165 789 1014 788 1021 802 1020 788 1015 867 1022 1166 1167 867 1016 1017 1023 874 1022 868 1017 869 1024 1168 1169 868 870 871 1170 1025 1024 459 871 1018 877 1026 1170 1019 460 459 878 1171 1172 802 460 1020 1173 1027 878 1021 803 802 1174 881 1173 1022 874 803 1174 1175 882 1023 875 874 1028 1031 1175 1024 1025 875 1176 1032 1028 1170 1026 1025 1177 1033 1176 1026 877 876 1178 1034 1177 876 878 1027 1179 1035 1178 1027 1173 881 1180 1036 1179 882 881 1174 1181 1037 1180 1031 882 1175 1182 1038 1181 1032 1031 1028 1183 1039 1182 1033 1032 1176 1184 1040 1183 1034 1033 1177 1185 1041 1184 1035 1034 1178 1186 1042 1185 1036 1035 1179 1187 1043 1186 1037 1036 1180 1187 1188 412 1181 1038 1037 1188 1189 413 1038 1182 1039 1044 1047 1189 1039 1183 1040 1190 1048 1044 1040 1184 1041 1191 1049 1190 1041 1185 1042 1192 900 1191 1042 1186 1043 1192 1193 901 1043 1187 412 1050 1053 1193 412 1188 413 1194 903 1050 413 1189 1047 1195 904 1194 1044 1048 1047 1056 1057 1195 1190 1049 1048 1058 381 1056 1191 900 1049 1059 1196 1197 1192 901 900 1060 373 1059 1193 1053 901 1061 1198 1199 903 1053 1050 909 1062 1061 904 903 1194 910 1200 1201 1057 904 1195 1201 1202 1063 1057 1056 381 1064 355 1063 382 381 1058 1065 1203 1204 382 1059 373 1204 1205 1066 373 1060 374 1206 914 1066 1061 1062 374 1069 343 1206 1062 909 908 1070 1068 1207 910 911 908 1207 1208 1071 1063 355 911 1208 1209 1072 1064 354 355 1210 1211 1212 913 354 1065 919 1074 1073 1066 914 913 920 1212 1213 1206 343 914 1075 1213 1214 1069 344 343 1076 1214 1215 916 344 1070 1077 1215 1216 917 916 1071 1216 1217 1078 918 917 1072 1217 1218 1079 1074 918 1073 1218 1219 1080 316 1074 919 1219 1220 1081 317 316 920 1221 1222 1083 922 317 1075 1223 929 1082 923 922 1076 930 1085 1223 1077 924 923 931 1084 1224 925 924 1078 1086 1224 1225 926 925 1079 1225 1226 1087 927 926 1080 1227 66 71 927 1081 928 1088 86 70 929 928 1082 1228 1089 70 1223 1085 929 1229 1090 1228 930 932 1085 1091 1229 1230 931 933 932 1231 1092 1230 1086 57 933 86 85 1232 1087 58 57 945 1100 946 21 1096 946 939 938 1092 1088 62 86 1233 1097 1096 70 1089 1088 1097 1234 1098 1228 1090 1089 1098 1235 1099 1229 1091 1090 1099 1236 1101 1230 1092 1091 1237 1238 1239 1231 1100 945 1106 953 1240 1102 1106 1241 1101 948 1099 1096 21 1233 1103 1241 1238 1234 1097 1233 1104 1238 1242 1235 1098 1234 1243 1105 1242 1236 1099 1235 1244 1241 1106 1101 1240 953 959 1110 958 1109 1107 958 1105 954 952 1102 1241 1103 1245 1108 1107 1103 1238 1104 1108 1246 1111 1105 1104 1242 963 1247 1248 1110 959 1243 1112 1248 1249 1249 1115 1113 1108 1111 258 1245 1107 1109 1248 1250 1249 1245 1246 1108 1116 1118 1114 1111 1247 963 963 1248 1112 1116 1251 1252 962 1113 964 1113 1112 1249 966 1117 1253 1117 819 965 273 1114 1118 1117 1118 1254 966 819 1117 824 641 967 1255 643 642 822 643 1255 967 1122 968 643 1256 1122 1257 829 635 1256 1257 637 1258 1259 1260 635 637 1257 971 1127 1126 635 829 831 976 1127 973 1126 831 830 1261 1262 1263 830 971 1126 1128 1264 980 971 973 1127 1265 1266 1267 977 976 973 978 1129 836 1264 975 977 1129 1268 837 1128 975 1264 1269 1270 1271 1128 980 979 1133 840 982 978 836 979 985 840 1132 836 1129 837 1272 986 1132 1268 983 837 1273 1274 1275 983 1268 984 843 1276 990 1133 982 984 1277 1278 990 840 1133 1132 992 991 1136 985 1132 986 564 538 1136 1135 987 986 1138 658 1279 1276 842 1135 1139 1279 1280 842 1276 843 1280 1281 1140 990 989 843 1282 995 1140 991 992 989 996 1143 1282 1136 538 992 997 1142 1283 564 9 538 1144 1283 1284 657 10 9 1145 1284 1285 1138 993 10 1146 1285 1286 994 993 1139 1147 1286 1287 995 994 1140 1287 1288 1148 1143 995 1282 1288 1289 1149 850 1143 996 1290 1291 1151 851 850 997 1292 1005 1150 999 851 1144 1006 1153 1292 1145 1000 999 1007 1152 1293 1146 1001 1000 1154 1293 1294 1002 1001 1147 1155 1294 1295 1003 1002 1148 1156 1295 1296 1004 1003 1149 1297 1298 1299 1005 1004 1150 1012 1158 1157 1292 1153 1005 1013 1299 1300 1006 860 1153 1159 1300 1301 1007 861 860 1302 1303 1304 1154 1009 861 1161 869 1160 1009 1155 1010 1162 1304 1305 1156 1011 1010 1306 1307 1308 1157 1158 1011 1164 1019 1163 1158 1012 1014 1165 1308 1309 1014 1013 1015 1166 1021 1165 1015 1159 1016 1167 1310 1311 1016 1160 869 1168 1023 1167 870 869 1161 1312 1313 1314 870 1162 1018 1315 1170 1169 1019 1018 1163 1171 877 1315 1164 1020 1019 1172 1316 1317 1021 1020 1165 1318 1173 1172 1166 1022 1021 1319 1174 1318 1167 1023 1022 1319 1029 1175 1023 1168 1024 1030 1320 1321 1169 1170 1024 1322 1176 1030 1315 877 1170 1323 1177 1322 877 1171 878 1324 1178 1323 878 1172 1173 1325 1179 1324 1173 1318 1174 1326 1180 1325 1175 1174 1319 1327 1181 1326 1028 1175 1029 1327 1328 1182 1176 1028 1030 1329 1183 1328 1177 1176 1322 1330 1184 1329 1178 1177 1323 1331 1185 1330 1179 1178 1324 1332 1186 1331 1180 1179 1325 1333 1187 1332 1326 1181 1180 1333 1334 1188 1327 1182 1181 1334 1045 1189 1183 1182 1328 1335 1336 1337 1183 1329 1184 1338 1190 1046 1184 1330 1185 1339 1191 1338 1185 1331 1186 1340 1192 1339 1186 1332 1187 1340 1051 1193 1188 1187 1333 1052 1341 1342 1188 1334 1189 1343 1194 1052 1189 1045 1044 1054 1195 1343 1044 1046 1190 1055 1344 1345 1338 1191 1190 1196 1058 1055 1339 1192 1191 1197 1346 1347 1340 1193 1192 1198 1060 1197 1051 1050 1193 1199 1348 1349 1194 1050 1052 1200 909 1199 1343 1195 1194 1201 1350 1351 1056 1195 1054 1352 1353 1354 1056 1055 1058 1203 1064 1202 1059 1058 1196 1204 1354 1355 1059 1197 1060 1356 1357 1358 1060 1198 1061 1067 1206 1205 1061 1199 909 1068 1358 1359 909 1200 910 1207 1359 1360 1201 1063 910 1360 1361 1208 1202 1064 1063 1362 1363 1210 1203 1065 1064 1364 1073 1209 1066 1065 1204 1212 919 1364 1205 1206 1066 1213 1211 1365 1067 1069 1206 1214 1365 1366 1068 1070 1069 1215 1366 1367 1207 1071 1070 1216 1367 1368 1072 1071 1208 1217 1368 1369 1073 1072 1209 1369 1370 1218 919 1073 1364 1371 1372 1373 920 919 1212 1372 1374 1221 1075 920 1213 1375 1082 1220 1076 1075 1214 1083 1223 1375 1215 1077 1076 1084 1222 1376 1216 1078 1077 1224 1376 1377 1079 1078 1217 1225 1377 1378 1080 1079 1218 1378 1379 1226 1081 1080 1219 1232 85 1226 1082 1081 1220 71 86 1232 1082 1375 1223 1228 65 256 930 1223 1083 1380 1229 256 1084 931 930 1381 1230 1380 931 1224 1086 1382 1231 1381 1086 1225 1087 1232 1227 71 1087 1226 85 1100 22 21 20 1233 21 945 1092 1231 71 70 86 1233 1383 1234 1228 70 65 1384 1235 1234 256 1229 1228 1235 1385 1236 1380 1230 1229 1236 1386 1240 1381 1231 1230 1387 20 1388 1100 1382 22 1244 1106 1389 1239 1241 1244 1240 1101 1236 1233 20 1383 1237 1390 1242 1234 1383 1384 1390 1391 1243 1385 1235 1384 1244 1095 1239 1386 1236 1385 1392 1109 1110 1389 1106 1240 1393 1245 1109 1246 1245 1394 1243 959 1105 1241 1239 1238 1247 1246 1395 1238 1237 1242 1393 1396 1397 1242 1390 1243 1248 1398 1250 1392 1110 1391 1393 1109 1392 1399 1249 1250 1246 1247 1111 1393 1394 1245 1251 1115 1399 1394 1395 1246 1400 1399 1250 1248 1247 1398 1116 1252 1254 1252 1401 1402 1113 1115 1114 1115 1249 1399 642 1253 1403 1117 1254 1253 1118 1116 1254 1253 1254 1404 966 1253 642 641 643 1122 823 822 1255 821 1405 822 1122 1256 637 822 1406 1256 1407 1408 829 1407 1257 1406 1408 1409 830 829 1257 1407 1410 1411 1412 830 829 1408 977 973 1413 830 1409 971 1264 977 1414 1409 972 971 980 1415 1266 1413 973 972 1266 1130 978 1413 1414 977 1416 1417 1418 1415 1264 1414 1131 1269 1268 1264 1415 980 1419 1133 984 980 1266 978 1420 1134 1419 978 1130 1129 1421 1422 1423 1131 1268 1129 1135 986 1273 984 1268 1269 1276 1135 1275 1419 984 1269 1424 1425 1426 1133 1419 1134 991 1278 1137 1272 1132 1134 1427 1428 536 986 1272 1273 537 765 766 1273 1275 1135 1279 767 1429 1277 1276 1275 1280 1429 1430 1277 990 1276 1431 1432 1433 1278 991 990 1141 1282 1281 1137 1136 991 1142 1433 1434 564 1136 562 1283 1434 1435 563 657 564 1284 1435 1436 658 1138 657 1285 1436 1437 1279 1139 1138 1286 1437 1438 1140 1139 1280 1287 1438 1439 1282 1140 1281 1440 1441 1442 996 1282 1141 1441 1443 1290 997 996 1142 1444 1150 1289 1144 997 1283 1151 1292 1444 1284 1145 1144 1152 1291 1445 1285 1146 1145 1293 1445 1446 1286 1147 1146 1294 1446 1447 1287 1148 1147 1295 1447 1448 1149 1148 1288 1296 1448 1449 1150 1149 1289 1450 1157 1296 1292 1150 1444 1299 1012 1450 1151 1006 1292 1300 1298 1451 1152 1007 1006 1301 1451 1452 1293 1154 1007 1453 1160 1301 1294 1155 1154 1304 1161 1453 1155 1295 1156 1305 1303 1454 1296 1157 1156 1455 1163 1305 1450 1012 1157 1308 1164 1455 1012 1299 1013 1456 1457 1458 1013 1300 1159 1310 1166 1309 1159 1301 1160 1311 1456 1459 1160 1453 1161 1460 1168 1311 1162 1161 1304 1460 1461 1169 1163 1162 1305 1312 1315 1461 1164 1163 1455 1316 1171 1312 1308 1165 1164 1462 1463 1464 1166 1165 1309 1465 1318 1317 1310 1167 1166 1466 1319 1465 1311 1168 1167 1466 1320 1029 1168 1460 1169 1467 1468 1469 1461 1315 1169 1470 1322 1321 1312 1171 1315 1471 1323 1470 1171 1316 1172 1472 1324 1471 1172 1317 1318 1473 1325 1472 1318 1465 1319 1474 1326 1473 1029 1319 1466 1474 1475 1327 1030 1029 1320 1475 1476 1328 1322 1030 1321 1477 1329 1476 1323 1322 1470 1478 1330 1477 1324 1323 1471 1479 1331 1478 1325 1324 1472 1480 1332 1479 1326 1325 1473 1481 1333 1480 1474 1327 1326 1481 1482 1334 1475 1328 1327 1482 1483 1045 1476 1329 1328 1483 1484 1046 1329 1477 1330 1335 1338 1484 1330 1478 1331 1485 1339 1335 1331 1479 1332 1486 1340 1485 1333 1332 1480 1486 1341 1051 1334 1333 1481 1342 1487 1488 1334 1482 1045 1489 1343 1342 1045 1483 1046 1489 1344 1054 1046 1484 1338 1345 1490 1491 1335 1339 1338 1346 1196 1345 1485 1340 1339 1347 1492 1493 1486 1051 1340 1348 1198 1347 1341 1052 1051 1349 1494 1495 1343 1052 1342 1350 1200 1349 1489 1054 1343 1351 1496 1497 1055 1054 1344 1498 1202 1351 1055 1345 1196 1354 1203 1498 1197 1196 1346 1355 1353 1499 1197 1347 1198 1500 1205 1355 1198 1348 1199 1358 1067 1500 1199 1349 1200 1359 1357 1501 1200 1350 1201 1360 1501 1502 1351 1202 1201 1362 1503 1504 1498 1203 1202 1505 1209 1361 1354 1204 1203 1210 1364 1505 1355 1205 1204 1211 1363 1506 1500 1067 1205 1365 1506 1507 1358 1068 1067 1366 1507 1508 1359 1207 1068 1367 1508 1509 1360 1208 1207 1368 1509 1510 1209 1208 1361 1369 1510 1511 1364 1209 1505 1512 1513 1371 1212 1364 1210 1514 1219 1370 1213 1212 1211 1373 1220 1514 1214 1213 1365 1221 1375 1373 1366 1215 1214 1222 1374 1515 1367 1216 1215 1376 1515 1516 1368 1217 1216 1377 1516 1517 1218 1217 1369 1378 1517 1518 1219 1218 1370 1519 1520 1521 1220 1219 1514 1227 1232 1379 1373 1375 1220 66 1519 1522 1221 1083 1375 78 64 1522 1083 1222 1084 1380 77 1523 1224 1084 1376 1524 1381 1523 1377 1225 1224 1525 1382 1524 1225 1378 1226 1227 1519 66 1226 1379 1232 22 1388 20 1387 1383 20 1100 1231 1382 65 71 66 1526 1384 1383 64 256 65 1384 1527 1385 77 1380 256 1385 1528 1386 1523 1381 1380 1386 1529 1389 1524 1382 1381 1387 1530 1531 1525 1388 22 1095 1244 1532 1239 1095 1533 1389 1240 1386 1383 1387 1526 1534 1237 1533 1527 1384 1526 1535 1390 1534 1528 1385 1527 1536 1391 1535 1528 1529 1386 1094 1533 1095 1389 1532 1244 1392 1396 1393 1393 1397 1394 1391 1110 1243 1237 1239 1533 1394 1537 1395 1390 1237 1534 1395 1538 1398 1391 1390 1535 1539 1397 1540 1396 1392 1536 1400 1250 1541 1542 1399 1400 1395 1398 1247 1397 1537 1394 1401 1251 1542 1537 1538 1395 1542 1400 1543 1398 1541 1250 1402 1544 1545 1546 1547 1403 1115 1251 1116 1251 1399 1542 1255 1403 1547 1253 1404 1403 1254 1252 1404 1404 1546 1403 642 1403 1255 643 822 1256 1548 1405 821 1548 1123 1405 1256 1406 1257 1405 1549 1406 1408 1550 1258 1550 1407 1549 1258 1551 1409 1408 1407 1550 1413 972 1552 1409 1408 1258 1263 1414 1413 1409 1551 972 1415 1414 1262 1551 1552 972 1553 1554 1555 1552 1263 1413 1130 1265 1417 1262 1414 1263 1417 1270 1131 1267 1415 1262 1270 1416 1556 1415 1267 1266 1557 1558 1559 1266 1265 1130 1422 1272 1134 1417 1131 1130 1273 1272 1421 1270 1269 1131 1560 1561 1562 1271 1419 1269 1277 1275 1424 1419 1271 1420 1278 1426 1563 1422 1134 1420 1137 1563 1427 1272 1422 1421 1427 535 562 1273 1421 1274 767 765 1564 1424 1275 1274 1429 1564 1565 1277 1424 1426 1431 1566 1567 1277 1426 1278 1568 1281 1430 1563 1137 1278 1433 1141 1568 1427 562 1137 1434 1432 1569 535 563 562 1435 1569 1570 766 658 563 1436 1570 1571 767 1279 658 1437 1571 1572 1429 1280 1279 1438 1572 1573 1281 1280 1430 1574 1440 1575 1141 1281 1568 1439 1576 1288 1142 1141 1433 1442 1289 1576 1283 1142 1434 1290 1444 1442 1435 1284 1283 1291 1443 1577 1436 1285 1284 1445 1577 1578 1437 1286 1285 1446 1578 1579 1438 1287 1286 1447 1579 1580 1439 1288 1287 1448 1580 1581 1289 1288 1576 1582 1583 1584 1444 1289 1442 1297 1450 1449 1290 1151 1444 1298 1582 1585 1291 1152 1151 1451 1585 1586 1445 1293 1152 1452 1586 1587 1446 1294 1293 1302 1453 1452 1294 1447 1295 1303 1588 1589 1295 1448 1296 1454 1589 1590 1449 1450 1296 1454 1306 1455 1450 1297 1299 1307 1591 1592 1299 1298 1300 1307 1593 1309 1300 1451 1301 1456 1310 1593 1453 1301 1452 1594 1595 1596 1453 1302 1304 1597 1460 1459 1305 1304 1303 1597 1313 1461 1454 1455 1305 1314 1598 1599 1308 1455 1306 1600 1316 1314 1307 1309 1308 1600 1601 1317 1310 1309 1593 1462 1465 1601 1456 1311 1310 1602 1466 1462 1459 1460 1311 1602 1603 1320 1460 1597 1461 1603 1604 1321 1313 1312 1461 1467 1470 1604 1314 1316 1312 1605 1471 1467 1316 1600 1317 1606 1472 1605 1317 1601 1465 1607 1473 1606 1465 1462 1466 1608 1474 1607 1320 1466 1602 1608 1609 1475 1321 1320 1603 1609 1610 1476 1470 1321 1604 1610 1611 1477 1471 1470 1467 1612 1478 1611 1472 1471 1605 1613 1479 1612 1473 1472 1606 1614 1480 1613 1474 1473 1607 1614 1615 1481 1608 1475 1474 1615 1616 1482 1609 1476 1475 1616 1617 1483 1610 1477 1476 1617 1336 1484 1478 1477 1611 1618 1619 1620 1478 1612 1479 1621 1485 1337 1479 1613 1480 1622 1486 1621 1481 1480 1614 1622 1487 1341 1482 1481 1615 1623 1624 1625 1482 1616 1483 1626 1489 1488 1483 1617 1484 1626 1490 1344 1484 1336 1335 1491 1627 1628 1337 1485 1335 1492 1346 1491 1621 1486 1485 1629 1630 1631 1622 1341 1486 1494 1348 1493 1487 1342 1341 1632 1633 1634 1489 1342 1488 1496 1350 1495 1626 1344 1489 1497 1632 1635 1345 1344 1490 1352 1498 1497 1346 1345 1491 1353 1636 1637 1347 1346 1492 1499 1637 1638 1347 1493 1348 1356 1500 1499 1349 1348 1494 1357 1639 1640 1349 1495 1350 1501 1640 1641 1350 1496 1351 1502 1641 1642 1497 1498 1351 1502 1643 1361 1352 1354 1498 1362 1505 1643 1354 1353 1355 1363 1504 1644 1499 1500 1355 1506 1644 1645 1356 1358 1500 1507 1645 1646 1357 1359 1358 1508 1646 1647 1501 1360 1359 1509 1647 1648 1502 1361 1360 1510 1648 1649 1505 1361 1643 1512 1650 1651 1210 1505 1362 1652 1370 1511 1211 1210 1363 1371 1514 1652 1506 1365 1211 1372 1513 1653 1507 1366 1365 1374 1653 1654 1508 1367 1366 1515 1654 1655 1509 1368 1367 1516 1655 1656 1510 1369 1368 1517 1656 1657 1370 1369 1511 1518 1657 1658 1514 1370 1652 1518 1659 1379 1373 1514 1371 1519 1227 1659 1372 1221 1373 1522 1521 1660 1374 1222 1221 78 1660 83 1515 1376 1222 72 1523 79 1377 1376 1516 1524 72 1661 1517 1378 1377 1662 1525 1661 1518 1379 1378 1519 1521 1522 1659 1227 1379 1388 1530 1387 1531 1526 1387 22 1382 1525 64 66 1522 1526 1663 1527 78 77 64 1664 1528 1527 79 1523 77 1528 254 1529 72 1524 1523 1529 253 1532 1524 1661 1525 1665 1531 1666 1662 1530 1388 1667 1668 1669 1533 1094 1670 1532 1389 1529 1526 1531 1663 1534 1670 1671 1527 1663 1664 1672 1535 1671 254 1528 1664 1673 1536 1672 253 1529 254 1674 1670 1094 1532 1093 1095 1396 1540 1397 1539 1537 1397 1536 1392 1391 1533 1670 1534 1537 1675 1538 1535 1534 1671 1538 1676 1541 1536 1535 1672 1677 1539 1678 1540 1396 1673 1543 1400 1679 1542 1543 1680 1538 1541 1398 1539 1675 1537 1544 1401 1680 1675 1676 1538 1545 1546 1402 1541 1679 1400 1545 1681 1682 1252 1402 1404 1251 1401 1252 1680 1401 1542 1547 1683 1684 821 823 1547 1404 1402 1546 1546 1683 1547 1255 1547 823 822 1405 1406 1124 1123 1548 1685 1686 1687 1406 1549 1407 1123 1688 1549 1689 1690 1691 1688 1259 1550 1260 1412 1551 1258 1550 1259 1692 1263 1552 1551 1258 1260 1693 1694 1695 1551 1412 1552 1267 1262 1554 1412 1692 1552 1265 1553 1418 1692 1261 1263 1696 1697 1698 1554 1262 1261 1699 1696 1700 1267 1554 1553 1556 1557 1271 1267 1553 1265 1701 1422 1420 1265 1418 1417 1702 1703 1704 1416 1270 1417 1561 1274 1421 1556 1271 1270 1424 1274 1560 1557 1420 1271 1705 1706 1707 1701 1420 1557 1563 1708 1428 1423 1422 1701 1709 1710 1428 1561 1421 1423 660 542 1711 1561 1560 1274 1564 764 1712 1424 1560 1425 1565 1712 1713 1426 1425 1708 1565 1714 1430 1708 1563 1426 1431 1568 1714 1428 1427 1563 1432 1567 1715 536 535 1427 1569 1715 1716 537 766 535 1570 1716 1717 765 767 766 1571 1717 1718 1564 1429 767 1572 1718 1719 1565 1430 1429 1720 1575 1721 1568 1430 1714 1573 1722 1439 1433 1568 1431 1722 1440 1576 1432 1434 1433 1441 1574 1723 1569 1435 1434 1443 1723 1724 1570 1436 1435 1577 1724 1725 1571 1437 1436 1578 1725 1726 1572 1438 1437 1579 1726 1727 1573 1439 1438 1580 1727 1728 1722 1576 1439 1729 1583 1730 1442 1576 1440 1581 1731 1449 1290 1442 1441 1582 1297 1731 1443 1291 1290 1585 1584 1732 1577 1445 1291 1586 1732 1733 1578 1446 1445 1734 1735 1736 1579 1447 1446 1587 1588 1302 1447 1580 1448 1589 1735 1737 1448 1581 1449 1590 1737 1738 1731 1297 1449 1590 1591 1306 1297 1582 1298 1592 1739 1740 1298 1585 1451 1592 1457 1593 1452 1451 1586 1458 1741 1742 1302 1452 1587 1458 1743 1459 1302 1588 1303 1594 1597 1743 1454 1303 1589 1594 1598 1313 1590 1306 1454 1599 1744 1745 1307 1306 1591 1746 1600 1599 1592 1593 1307 1746 1463 1601 1457 1456 1593 1464 1747 1748 1458 1459 1456 1749 1602 1464 1743 1597 1459 1749 1750 1603 1597 1594 1313 1750 1468 1604 1313 1598 1314 1751 1752 1753 1599 1600 1314 1754 1605 1469 1600 1746 1601 1755 1606 1754 1601 1463 1462 1756 1607 1755 1462 1464 1602 1757 1608 1756 1603 1602 1749 1757 1758 1609 1604 1603 1750 1758 1759 1610 1467 1604 1468 1759 1760 1611 1605 1467 1469 1761 1612 1760 1606 1605 1754 1762 1613 1761 1607 1606 1755 1763 1614 1762 1608 1607 1756 1763 1764 1615 1757 1609 1608 1764 1765 1616 1758 1610 1609 1765 1766 1617 1759 1611 1610 1766 1767 1336 1612 1611 1760 1767 1768 1337 1612 1761 1613 1618 1621 1768 1613 1762 1614 1769 1622 1618 1615 1614 1763 1769 1770 1487 1616 1615 1764 1770 1771 1488 1616 1765 1617 1623 1626 1771 1617 1766 1336 1623 1627 1490 1336 1767 1337 1772 1773 1774 1768 1621 1337 1775 1492 1628 1618 1622 1621 1775 1776 1493 1769 1487 1622 1629 1494 1776 1770 1488 1487 1629 1777 1495 1626 1488 1771 1632 1496 1777 1623 1490 1626 1778 1779 1780 1491 1490 1627 1636 1352 1635 1492 1491 1628 1637 1779 1781 1493 1492 1775 1782 1783 1784 1493 1776 1494 1639 1356 1638 1495 1494 1629 1640 1783 1785 1495 1777 1496 1641 1785 1786 1496 1632 1497 1787 1788 1789 1635 1352 1497 1642 1503 1643 1352 1636 1353 1504 1788 1790 1353 1637 1499 1644 1790 1791 1499 1638 1356 1645 1791 1792 1639 1357 1356 1646 1792 1793 1640 1501 1357 1647 1793 1794 1641 1502 1501 1795 1796 1797 1642 1643 1502 1798 1650 1795 1362 1643 1503 1649 1799 1511 1363 1362 1504 1512 1652 1799 1644 1506 1363 1513 1651 1800 1645 1507 1506 1653 1800 1801 1646 1508 1507 1654 1801 1802 1647 1509 1508 1655 1802 1803 1648 1510 1509 1656 1803 1804 1649 1511 1510 1657 1804 1805 1652 1511 1799 1806 1807 1808 1371 1652 1512 1658 1520 1659 1513 1372 1371 1521 1807 1809 1653 1374 1372 1660 1809 1810 1654 1515 1374 83 1810 1811 1655 1516 1515 91 1812 1813 1656 1517 1516 1814 1661 74 1657 1518 1517 1815 1662 1814 1658 1659 1518 1809 1660 1521 1520 1519 1659 1530 1666 1531 1665 1663 1531 1388 1525 1662 78 1522 1660 1816 1664 1663 83 79 78 1664 1817 254 79 73 72 1818 1819 1820 74 1661 72 253 1821 1093 1814 1662 1661 1819 1665 1822 1530 1815 1666 1674 1094 1823 1824 1670 1674 1093 1532 253 1663 1665 1816 1825 1671 1824 1664 1816 1817 1672 1825 1826 254 1817 252 1827 1673 1826 1821 253 252 1824 1674 1667 1823 1094 1093 1540 1678 1539 1677 1675 1539 1673 1396 1536 1670 1824 1671 1828 1676 1675 1671 1825 1672 1676 1829 1679 1673 1672 1826 1830 1677 1831 1678 1540 1827 1680 1832 1833 1833 1681 1544 1676 1679 1541 1828 1675 1677 1832 1834 1833 1828 1829 1676 1682 1683 1545 1679 1835 1543 1543 1832 1680 1682 1836 1837 1401 1544 1402 1544 1680 1833 1548 1684 1838 1684 821 1547 1546 1545 1683 1684 1683 1839 1548 821 1684 1405 1123 1549 1121 1125 1124 1120 1125 1121 1549 1688 1550 1125 1840 1688 1841 1410 1260 1840 1841 1259 1842 1843 1844 1260 1259 1841 1695 1261 1692 1260 1410 1412 1554 1261 1694 1692 1412 1411 1845 1846 1847 1411 1695 1692 1418 1848 1697 1694 1261 1695 1697 1699 1416 1554 1694 1555 1699 1558 1556 1848 1553 1555 1849 1850 1851 1553 1848 1418 1704 1423 1701 1697 1416 1418 1703 1561 1423 1416 1699 1556 1852 1853 1854 1558 1557 1556 1425 1560 1705 1559 1701 1557 1708 1425 1707 1704 1701 1559 1855 1856 1857 1703 1423 1704 536 1710 713 1561 1703 1562 764 543 1858 1562 1705 1560 1712 1858 1859 1707 1425 1705 1860 1861 1862 1707 1709 1708 1713 1566 1714 1709 1428 1708 1567 1861 1863 1710 536 1428 1715 1863 1864 536 713 537 1716 1864 1865 544 765 537 1717 1865 1866 764 1564 765 1718 1866 1867 1712 1565 1564 1868 1721 1869 1713 1714 1565 1719 1870 1573 1431 1714 1566 1870 1575 1722 1567 1432 1431 1871 1574 1720 1715 1569 1432 1723 1871 1872 1716 1570 1569 1724 1872 1873 1717 1571 1570 1725 1873 1874 1718 1572 1571 1726 1874 1875 1719 1573 1572 1727 1875 1876 1870 1722 1573 1728 1876 1877 1575 1440 1722 1728 1878 1581 1441 1440 1574 1878 1583 1731 1723 1443 1441 1584 1729 1879 1724 1577 1443 1732 1879 1880 1725 1578 1577 1733 1880 1881 1726 1579 1578 1733 1882 1587 1727 1580 1579 1882 1735 1588 1580 1728 1581 1737 1734 1883 1581 1878 1731 1884 1885 1886 1583 1582 1731 1738 1739 1591 1582 1584 1585 1740 1885 1887 1585 1732 1586 1740 1741 1457 1587 1586 1733 1742 1888 1889 1588 1587 1882 1742 1595 1743 1589 1588 1735 1596 1890 1891 1590 1589 1737 1596 1744 1598 1738 1591 1590 1745 1892 1893 1592 1591 1739 1894 1746 1745 1740 1457 1592 1894 1747 1463 1741 1458 1457 1748 1895 1896 1742 1743 1458 1897 1749 1748 1595 1594 1743 1897 1898 1750 1594 1596 1598 1898 1899 1468 1598 1744 1599 1899 1900 1469 1745 1746 1599 1751 1754 1900 1746 1894 1463 1901 1755 1751 1463 1747 1464 1902 1756 1901 1464 1748 1749 1903 1757 1902 1750 1749 1897 1903 1904 1758 1468 1750 1898 1904 1905 1759 1469 1468 1899 1905 1906 1760 1754 1469 1900 1907 1761 1906 1755 1754 1751 1908 1762 1907 1756 1755 1901 1909 1763 1908 1902 1757 1756 1909 1910 1764 1903 1758 1757 1910 1911 1765 1904 1759 1758 1911 1912 1766 1905 1760 1759 1912 1913 1767 1906 1761 1760 1913 1619 1768 1762 1761 1907 1620 1914 1915 1762 1908 1763 1916 1769 1620 1764 1763 1909 1916 1917 1770 1765 1764 1910 1917 1624 1771 1766 1765 1911 1625 1918 1919 1766 1912 1767 1625 1920 1627 1767 1913 1768 1920 1921 1628 1619 1618 1768 1772 1775 1921 1620 1769 1618 1772 1630 1776 1769 1916 1770 1631 1922 1923 1917 1771 1770 1631 1633 1777 1624 1623 1771 1634 1924 1925 1625 1627 1623 1634 1926 1635 1628 1627 1920 1779 1636 1926 1775 1628 1921 1781 1778 1927 1776 1775 1772 1781 1928 1638 1776 1630 1629 1928 1783 1639 1777 1629 1631 1785 1782 1929 1777 1633 1632 1786 1929 1930 1632 1634 1635 1786 1931 1642 1635 1926 1636 1931 1788 1503 1636 1779 1637 1790 1787 1932 1637 1781 1638 1791 1932 1933 1638 1928 1639 1792 1933 1934 1783 1640 1639 1793 1934 1935 1785 1641 1640 1936 1797 1937 1786 1642 1641 1794 1938 1648 1931 1503 1642 1938 1796 1649 1504 1503 1788 1796 1650 1799 1790 1644 1504 1939 1651 1798 1791 1645 1644 1800 1939 1940 1792 1646 1645 1801 1940 1941 1793 1647 1646 1802 1941 1942 1794 1648 1647 1803 1942 1943 1938 1649 1648 1804 1943 1944 1796 1799 1649 1945 1808 1946 1650 1512 1799 1805 1947 1658 1513 1512 1651 1947 1807 1520 1800 1653 1513 1809 1806 1948 1801 1654 1653 1810 1948 1949 1802 1655 1654 1950 84 1951 1803 1656 1655 1811 75 73 1657 1656 1804 60 1814 76 1805 1658 1657 1952 1815 60 1947 1520 1658 1948 1810 1809 1807 1521 1520 1666 1822 1665 1819 1816 1665 1530 1662 1815 1660 1810 83 1953 1817 1816 73 83 1811 68 252 1817 75 74 73 252 67 1821 74 76 1814 1821 1954 1823 60 1815 1814 1955 1956 1957 1952 1822 1666 1667 1674 1958 1824 1667 1669 1823 1093 1821 1816 1819 1953 1959 1825 1669 1817 1953 68 1960 1826 1959 67 252 68 1961 1827 1960 1821 67 1954 1831 1677 1678 1958 1674 1823 1830 1828 1677 1829 1828 1962 1827 1540 1673 1824 1669 1825 1835 1829 1963 1825 1959 1826 1830 1964 1965 1826 1960 1827 1832 1966 1834 1831 1678 1961 1833 1834 1967 1835 1832 1543 1829 1835 1679 1830 1962 1828 1836 1681 1967 1962 1963 1829 1968 1967 1834 1832 1835 1966 1682 1837 1839 1837 1969 1970 1544 1681 1545 1681 1833 1967 1124 1838 1971 1684 1839 1838 1683 1682 1839 1838 1839 1972 1548 1838 1124 1125 1688 1123 1973 1120 1119 1973 1974 1120 1688 1840 1259 1120 1975 1840 1976 1977 1410 1976 1841 1975 1977 1978 1411 1410 1841 1976 1843 1979 1980 1411 1410 1977 1555 1694 1846 1411 1978 1695 1848 1555 1845 1978 1693 1695 1981 1982 1983 1846 1694 1693 1984 1985 1986 1845 1555 1846 1700 1849 1558 1848 1845 1698 1849 1987 1559 1848 1698 1697 1988 1987 1851 1697 1696 1699 1853 1562 1703 1700 1558 1699 1705 1562 1852 1558 1849 1559 1989 1990 1991 1987 1704 1559 1709 1707 1855 1702 1704 1987 1710 1857 714 1853 1703 1702 1992 661 1711 1853 1852 1562 1858 662 1993 1852 1706 1705 1859 1993 1994 1855 1707 1706 1859 1995 1713 1709 1855 1857 1995 1861 1566 1857 1710 1709 1996 1863 1860 713 1710 714 1864 1996 1997 713 542 544 1865 1997 1998 543 764 544 1866 1998 1999 1858 1712 764 2000 1869 2001 1859 1713 1712 1867 2002 1719 1995 1566 1713 2002 1721 1870 1566 1861 1567 2003 1720 1868 1863 1715 1567 2004 1871 2003 1864 1716 1715 1872 2004 2005 1865 1717 1716 1873 2005 2006 1866 1718 1717 1874 2006 2007 1867 1719 1718 1875 2007 2008 2002 1870 1719 1876 2008 2009 1721 1575 1870 2010 2011 2012 1720 1574 1575 1877 1730 1878 1871 1723 1574 2013 1729 2011 1872 1724 1723 2014 1879 2013 1873 1725 1724 1880 2014 2015 1874 1726 1725 2016 2017 2018 1875 1727 1726 1881 1736 1882 1727 1876 1728 2019 1734 2017 1728 1877 1878 1883 2019 2020 1878 1730 1583 1883 2021 1738 1583 1729 1584 2021 1885 1739 1584 1879 1732 1887 1884 2022 1732 1880 1733 1887 1888 1741 1882 1733 1881 1889 2023 2024 1735 1882 1736 1889 1890 1595 1737 1735 1734 1891 2025 2026 1738 1737 1883 1891 1892 1744 2021 1739 1738 2027 2028 2029 1740 1739 1885 2030 1894 1893 1887 1741 1740 2030 1895 1747 1888 1742 1741 2031 2032 2033 1889 1595 1742 2034 1897 1896 1890 1596 1595 2034 2035 1898 1596 1891 1744 2035 2036 1899 1744 1892 1745 2036 1752 1900 1894 1745 1893 1753 2037 2038 1894 2030 1747 2039 1901 1753 1747 1895 1748 2040 1902 2039 1748 1896 1897 2040 2041 1903 1898 1897 2034 2041 2042 1904 1899 1898 2035 2042 2043 1905 1900 1899 2036 2043 2044 1906 1751 1900 1752 2044 2045 1907 1901 1751 1753 2046 1908 2045 1902 1901 2039 2047 1909 2046 2040 1903 1902 2047 2048 1910 2041 1904 1903 2048 2049 1911 2042 1905 1904 2049 2050 1912 2043 1906 1905 2050 2051 1913 2044 1907 1906 2051 1914 1619 1908 1907 2045 2052 2053 2054 1909 1908 2046 2055 1916 1915 1910 1909 2047 2055 2056 1917 1911 1910 2048 2056 1918 1624 1912 1911 2049 1919 2057 2058 1912 2050 1913 1919 2059 1920 1913 2051 1619 2059 1773 1921 1619 1914 1620 1774 2060 2061 1915 1916 1620 1774 1922 1630 1916 2055 1917 1923 2062 2063 2056 1624 1917 1923 1924 1633 1918 1625 1624 1925 2064 2065 1919 1920 1625 1925 1780 1926 2059 1921 1920 2066 1778 2067 1772 1921 1773 1927 2066 2068 1630 1772 1774 1927 1784 1928 1631 1630 1922 2069 1782 2070 1633 1631 1923 1929 2069 2071 1633 1924 1634 2072 2073 2074 1634 1925 1926 1930 1789 1931 1779 1926 1780 2075 1787 2073 1779 1778 1781 1932 2075 2076 1781 1927 1928 1933 2076 2077 1928 1784 1783 1934 2077 2078 1782 1785 1783 2079 1937 2080 1929 1786 1785 1935 2081 1794 1930 1931 1786 2081 1797 1938 1931 1789 1788 2082 1795 1936 1787 1790 1788 2083 1798 2082 1932 1791 1790 2084 1939 2083 1933 1792 1791 1940 2084 2085 1934 1793 1792 1941 2085 2086 1935 1794 1793 1942 2086 2087 2081 1938 1794 1943 2087 2088 1797 1796 1938 2089 1946 2090 1795 1650 1796 1944 2091 1805 1798 1651 1650 2091 1808 1947 1939 1800 1651 2092 1806 1945 1940 1801 1800 1948 2092 2093 1941 1802 1801 1949 2093 2094 1942 1803 1802 1949 2095 1811 1943 1804 1803 2095 84 75 1804 1944 1805 61 1950 87 2091 1947 1805 2096 1952 59 1947 1808 1807 1948 2093 1949 1806 1809 1807 1822 1820 1819 1818 1953 1819 1666 1815 1952 1810 1949 1811 1953 2097 68 1811 2095 75 2098 82 81 75 84 76 2099 1954 67 61 60 76 1954 2100 1958 60 59 1952 2101 1818 2102 1822 2096 1820 1668 1667 2103 2104 1669 1668 1958 1823 1954 1953 1818 2097 1959 2104 2105 68 2097 69 2106 1960 2105 67 69 2099 2107 1961 2106 2100 1954 2099 2104 1668 2108 2103 1667 1958 1831 1964 1830 1830 1965 1962 1961 1678 1827 1669 2104 1959 1962 2109 1963 1960 1959 2105 1963 2110 1966 1961 1960 2106 1957 1965 1955 1964 1831 2107 1968 1834 2111 2112 1967 1968 1963 1966 1835 1965 2109 1962 1969 1836 2112 2109 2110 1963 2112 1968 2113 1966 2111 1834 1970 2114 2115 2116 1971 2117 1681 1836 1682 1836 1967 2112 1121 1971 2116 1838 1972 1971 1839 1837 1972 1972 2117 1971 1124 1971 1121 1125 1120 1840 2118 1974 1973 2118 1689 1974 1840 1975 1841 1974 2119 1975 1977 2120 2121 2120 1976 2119 2121 2122 1978 1977 1976 2120 1846 1693 2123 1978 1977 2121 2124 2125 2126 1978 2122 1693 1698 1845 1982 2123 1693 2122 1696 1981 1985 1847 1846 2123 1985 1850 1700 1982 1845 1847 2127 2128 2129 1698 1982 1981 2130 2127 2131 1698 1981 1696 2132 1853 1702 1696 1985 1700 2133 1854 2132 1700 1850 1849 1990 1706 1852 1851 1987 1849 1855 1706 1989 1987 1988 1702 1856 1989 2134 2132 1702 1988 714 2135 1711 2132 1854 1853 2136 662 659 1854 1990 1852 1993 2136 2137 1989 1706 1990 2138 2139 2140 1855 1989 1856 1994 1862 1995 2135 1857 1856 2141 1860 2139 1857 2135 714 2142 1996 2141 714 1711 542 1997 2142 2143 542 660 543 1998 2143 2144 662 1858 543 2145 2001 2146 1993 1859 1858 1999 2147 1867 1994 1995 1859 2147 1869 2002 1995 1862 1861 2148 1868 2000 1861 1860 1863 2149 2003 2148 1996 1864 1863 2150 2004 2149 1997 1865 1864 2151 2005 2150 1998 1866 1865 2006 2151 2152 1999 1867 1866 2007 2152 2153 2147 2002 1867 2008 2153 2154 1869 1721 2002 2155 2012 2156 1868 1720 1721 2009 2157 1877 2003 1871 1720 2157 2011 1730 1871 2004 1872 2158 2013 2010 2005 1873 1872 2159 2014 2158 2006 1874 1873 2015 2159 2160 2007 1875 1874 2015 2161 1881 2008 1876 1875 2161 2017 1736 1876 2009 1877 2162 2019 2016 1877 2157 1730 2020 2162 2163 1730 2011 1729 2020 1886 2021 1879 1729 2013 2164 1884 2165 1879 2014 1880 2166 2167 2168 1880 2015 1881 2022 2023 1888 1736 1881 2161 2024 2167 2169 1734 1736 2017 2024 2025 1890 1883 1734 2019 2026 2170 2171 2021 1883 2020 2026 2172 1892 1886 1885 2021 2172 2173 1893 1887 1885 1884 2173 2028 2030 2022 1888 1887 2028 2174 1895 2023 1889 1888 2174 2175 1896 2024 1890 1889 2031 2034 2175 2025 1891 1890 2031 2176 2035 1891 2026 1892 2176 2177 2036 1892 2172 1893 2177 2037 1752 2030 1893 2173 2178 2179 2180 2030 2028 1895 2181 2039 2038 1895 2174 1896 2182 2040 2181 1896 2175 2034 2182 2183 2041 2035 2034 2031 2183 2184 2042 2036 2035 2176 2184 2185 2043 1752 2036 2177 2185 2186 2044 1753 1752 2037 2186 2187 2045 2039 1753 2038 2188 2046 2187 2040 2039 2181 2188 2189 2047 2182 2041 2040 2189 2190 2048 2183 2042 2041 2190 2191 2049 2184 2043 2042 2191 2192 2050 2185 2044 2043 2192 2193 2051 2186 2045 2044 2193 2194 1914 2187 2046 2045 2194 2195 1915 2047 2046 2188 2052 2055 2195 2048 2047 2189 2052 2196 2056 2049 2048 2190 2196 2057 1918 2050 2049 2191 2197 2198 2199 2050 2192 2051 2058 2200 2059 2051 2193 1914 2200 2060 1773 1914 2194 1915 2061 2201 2202 2195 2055 1915 2061 2062 1922 2055 2052 2056 2063 2203 2204 2196 1918 2056 2063 2064 1924 2057 1919 1918 2065 2205 2206 2058 2059 1919 2065 2067 1780 2200 1773 2059 2207 2066 2208 1774 1773 2060 2209 2210 2211 1922 1774 2061 2068 2070 1784 1923 1922 2062 2212 2069 2210 1924 1923 2063 2071 2212 2213 1924 2064 1925 2071 2214 1930 1925 2065 1780 2214 2073 1789 1778 1780 2067 2215 2075 2072 1778 2066 1927 2076 2215 2216 1927 2068 1784 2077 2216 2217 1784 2070 1782 2218 2080 2219 2069 1929 1782 2078 2220 1935 2071 1930 1929 2220 1937 2081 1930 2214 1789 2221 1936 2079 1789 2073 1787 2222 2082 2221 2075 1932 1787 2223 2083 2222 2076 1933 1932 2224 2084 2223 2077 1934 1933 2085 2224 2225 2078 1935 1934 2086 2225 2226 2220 2081 1935 2087 2226 2227 1937 1797 2081 2228 2090 2229 1936 1795 1797 2088 2230 1944 2082 1798 1795 2230 1946 2091 1798 2083 1939 2231 1945 2089 2084 1940 1939 2232 2092 2231 2085 1941 1940 2093 2232 2233 2086 1942 1941 2094 2233 2234 2087 1943 1942 2094 1951 2095 1943 2088 1944 2235 1950 2236 1944 2230 2091 87 2235 2237 1946 1808 2091 89 2096 88 1808 1945 1806 2093 2233 2094 2092 1948 1806 1820 2102 1818 2101 2097 1818 1822 1952 2096 2095 1949 2094 2238 69 2097 2095 1951 84 69 2239 2099 84 1950 61 2099 2240 2100 61 87 59 2100 2241 2103 88 2096 59 2242 2101 2243 1820 89 2102 2108 1668 2244 2104 2108 2245 2103 1958 2100 2097 2101 2238 2246 2105 2245 2239 69 2238 2247 2106 2246 2099 2239 2240 2248 2107 2247 2100 2240 2241 2245 2108 2249 2244 1668 2103 1964 1955 1965 1957 2109 1965 2107 1831 1961 2104 2245 2105 2109 2250 2110 2105 2246 2106 2110 2251 2111 2107 2106 2247 2252 1957 1956 1955 1964 2248 2113 1968 2253 2112 2113 2254 2110 2111 1966 1957 2250 2109 2114 1969 2254 2250 2251 2110 2115 2117 1970 2111 2253 1968 2115 2255 2256 1837 1970 1972 1836 1969 1837 2254 1969 2112 2116 2257 2258 1119 1121 2116 1972 1970 2117 2116 2117 2257 1973 1119 2116 1120 1974 1975 1690 1689 2118 2259 2260 2261 1975 2119 1976 1689 2262 2119 2121 2263 1844 2262 2263 2120 1844 1980 2122 2121 2120 2263 2126 1847 2123 2121 1844 2122 1982 1847 2125 2122 1980 2123 2264 2265 2266 1980 2126 2123 2267 2264 2268 2125 1847 2126 1850 1984 2128 1982 2125 1983 2128 2130 1851 1981 1983 1986 2130 2269 1988 1981 1986 1985 2270 2271 2272 1985 1984 1850 2273 1990 1854 1850 2128 1851 2274 1991 2273 1851 2130 1988 2275 2276 2277 2269 2132 1988 2135 1856 2278 2133 2132 2269 2279 1992 2278 1854 2133 2273 2280 2136 708 1991 1990 2273 2137 2280 2281 1989 1991 2134 2137 2282 1994 1856 2134 2278 2282 2139 1862 2135 2278 1992 2283 2141 2138 2135 1992 1711 2284 2142 2283 1711 661 660 2143 2284 2285 660 659 662 2286 2146 2287 2136 1993 662 2144 2288 1999 2137 1994 1993 2288 2001 2147 1994 2282 1862 2289 2000 2145 1862 2139 1860 2290 2148 2289 1860 2141 1996 2291 2149 2290 2142 1997 1996 2292 2150 2291 2143 1998 1997 2293 2151 2292 2144 1999 1998 2152 2293 2294 2288 2147 1999 2153 2294 2295 2001 1869 2147 2296 2156 2297 2000 1868 1869 2154 2298 2009 2148 2003 1868 2298 2012 2157 2003 2149 2004 2299 2010 2155 2004 2150 2005 2300 2158 2299 2151 2006 2005 2301 2159 2300 2152 2007 2006 2160 2301 2302 2153 2008 2007 2160 2018 2161 2008 2154 2009 2303 2016 2304 2009 2298 2157 2305 2162 2303 2157 2012 2011 2306 2307 2308 2011 2010 2013 2163 2165 1886 2014 2013 2158 2309 2164 2307 2014 2159 2015 2164 2310 2022 2015 2160 2161 2310 2167 2023 2017 2161 2018 2311 2312 2313 2019 2017 2016 2169 2170 2025 2020 2019 2162 2314 2315 2316 1886 2020 2163 2171 2317 2172 2165 1884 1886 2317 2029 2173 2164 2022 1884 2318 2027 2319 2310 2023 2022 2027 2320 2174 2167 2024 2023 2320 2032 2175 2024 2169 2025 2033 2321 2322 2170 2026 2025 2033 2323 2176 2026 2171 2172 2323 2324 2177 2172 2317 2173 2324 2325 2037 2028 2173 2029 2325 2326 2038 2028 2027 2174 2327 2181 2326 2174 2320 2175 2328 2182 2327 2175 2032 2031 2328 2329 2183 2176 2031 2033 2329 2330 2184 2177 2176 2323 2330 2331 2185 2037 2177 2324 2331 2332 2186 2038 2037 2325 2332 2333 2187 2181 2038 2326 2333 2334 2188 2182 2181 2327 2334 2335 2189 2328 2183 2182 2335 2336 2190 2329 2184 2183 2336 2337 2191 2330 2185 2184 2337 2338 2192 2331 2186 2185 2338 2339 2193 2332 2187 2186 2339 2340 2194 2333 2188 2187 2340 2053 2195 2334 2189 2188 2054 2341 2342 2190 2189 2335 2054 2343 2196 2191 2190 2336 2343 2344 2057 2192 2191 2337 2344 2345 2058 2192 2338 2193 2345 2198 2200 2193 2339 2194 2198 2201 2060 2194 2340 2195 2202 2346 2347 2053 2052 2195 2202 2203 2062 2052 2054 2196 2348 2349 2350 2343 2057 2196 2204 2205 2064 2344 2058 2057 2206 2349 2351 2345 2200 2058 2206 2208 2067 2198 2060 2200 2352 2207 2353 2061 2060 2201 2207 2354 2068 2062 2061 2202 2354 2210 2070 2063 2062 2203 2355 2212 2209 2064 2063 2204 2356 2357 2358 2064 2205 2065 2213 2074 2214 2067 2065 2206 2359 2072 2357 2066 2067 2208 2360 2215 2359 2066 2207 2068 2216 2360 2361 2068 2354 2070 2362 2219 2363 2070 2210 2069 2217 2364 2078 2212 2071 2069 2364 2080 2220 2071 2213 2214 2365 2079 2218 2214 2074 2073 2366 2221 2365 2073 2072 2075 2367 2222 2366 2215 2076 2075 2368 2223 2367 2216 2077 2076 2369 2224 2368 2217 2078 2077 2225 2369 2370 2364 2220 2078 2226 2370 2371 2080 1937 2220 2372 2229 2373 2079 1936 1937 2227 2374 2088 2221 2082 1936 2374 2090 2230 2082 2222 2083 2375 2089 2228 2083 2223 2084 2376 2231 2375 2224 2085 2084 2377 2232 2376 2225 2086 2085 2233 2377 94 2226 2087 2086 2378 2379 97 2227 2088 2087 2234 2236 1951 2088 2374 2230 2380 2235 2379 2230 2090 1946 2237 2380 2381 1946 2089 1945 2237 90 88 2231 2092 1945 94 2234 2233 2232 2093 2092 2102 2243 2101 2101 2242 2238 1820 2096 89 2094 2234 1951 2382 2239 2238 1950 1951 2236 2383 2240 2239 87 1950 2235 2240 2384 2241 88 87 2237 2241 2385 2244 88 90 89 2386 2242 2387 2102 91 2243 2249 2108 2388 2245 2249 2389 2244 2103 2241 2238 2242 2382 2246 2389 2390 2239 2382 2383 2391 2247 2390 2384 2240 2383 2392 2248 2391 2385 2241 2384 2389 2249 2393 2108 2244 2388 2252 2250 1957 2394 2395 2396 2248 1964 2107 2389 2246 2245 2397 2251 2250 2246 2390 2247 2251 2398 2253 2247 2391 2248 2395 2252 2399 1956 1955 2392 2400 2113 2401 2254 2400 2402 2251 2253 2111 2397 2250 2252 2400 2403 2402 2397 2398 2251 2256 2257 2115 2253 2401 2113 2113 2400 2254 2256 2404 2405 1969 2114 1970 2114 2254 2402 2118 2258 2406 2258 1973 2116 2117 2115 2257 2258 2257 2407 2118 1973 2258 1974 1689 2119 2408 1691 1690 1685 1691 2408 2119 2262 2120 2262 1691 2409 2410 2411 2412 2409 1842 2263 2413 2414 2415 1844 2263 1842 2415 2416 2417 1844 1843 1980 1983 2125 2265 1980 1979 2126 1986 1983 2264 2124 2126 1979 1984 2267 2129 2265 2125 2124 2418 2419 2420 2264 1983 2265 2421 2422 2419 1986 2264 2267 2131 2270 2269 1986 2267 1984 2423 2273 2133 1984 2129 2128 2424 2425 2426 2128 2127 2130 2134 1991 2275 2131 2269 2130 2278 2134 2277 2270 2133 2269 2427 2428 558 2423 2133 2270 557 666 567 2273 2423 2274 2429 2280 566 2275 1991 2274 2430 2431 2432 2134 2275 2277 2281 2140 2282 2278 2277 2279 2433 2138 2432 1992 2279 705 2434 2283 2433 1992 705 661 2435 2284 2434 661 698 659 2436 2437 2287 659 708 2136 2285 2438 2144 2280 2137 2136 2438 2146 2288 2137 2281 2282 2439 2145 2286 2282 2140 2139 2440 2289 2439 2139 2138 2141 2441 2290 2440 2141 2283 2142 2442 2291 2441 2284 2143 2142 2443 2292 2442 2285 2144 2143 2444 2293 2443 2438 2288 2144 2445 2446 2447 2146 2001 2288 2447 2448 2297 2145 2000 2001 2295 2449 2154 2289 2148 2000 2449 2156 2298 2148 2290 2149 2450 2155 2296 2149 2291 2150 2451 2299 2450 2150 2292 2151 2452 2300 2451 2293 2152 2151 2453 2301 2452 2294 2153 2152 2454 2455 2456 2295 2154 2153 2302 2304 2018 2154 2449 2298 2457 2303 2456 2298 2156 2012 2458 2305 2457 2012 2155 2010 2305 2459 2163 2010 2299 2158 2459 2307 2165 2159 2158 2300 2460 2309 2306 2159 2301 2160 2309 2168 2310 2018 2160 2302 2461 2166 2462 2016 2018 2304 2166 2463 2169 2162 2016 2303 2463 2312 2170 2163 2162 2305 2312 2464 2171 2165 2163 2459 2464 2315 2317 2307 2164 2165 2315 2319 2029 2309 2310 2164 2465 2318 2466 2168 2167 2310 2318 2467 2320 2166 2169 2167 2467 2321 2032 2169 2463 2170 2322 2468 2469 2312 2171 2170 2322 2470 2323 2171 2464 2317 2470 2471 2324 2317 2315 2029 2471 2472 2325 2027 2029 2319 2472 2473 2326 2320 2027 2318 2473 2474 2327 2320 2467 2032 2178 2328 2474 2032 2321 2033 2178 2475 2329 2323 2033 2322 2475 2476 2330 2324 2323 2470 2476 2477 2331 2325 2324 2471 2477 2478 2332 2326 2325 2472 2478 2479 2333 2327 2326 2473 2479 2480 2334 2328 2327 2474 2480 2481 2335 2178 2329 2328 2481 2482 2336 2475 2330 2329 2482 2483 2337 2476 2331 2330 2483 2484 2338 2477 2332 2331 2484 2485 2339 2478 2333 2332 2485 2486 2340 2479 2334 2333 2486 2341 2053 2480 2335 2334 2487 2488 2489 2336 2335 2481 2342 2490 2343 2337 2336 2482 2490 2491 2344 2338 2337 2483 2491 2199 2345 2339 2338 2484 2492 2197 2493 2339 2485 2340 2197 2346 2201 2340 2486 2053 2494 2495 2496 2341 2054 2053 2347 2497 2203 2054 2342 2343 2497 2498 2204 2490 2344 2343 2498 2349 2205 2491 2345 2344 2499 2500 2501 2199 2198 2345 2351 2353 2208 2197 2201 2198 2502 2352 2501 2202 2201 2346 2352 2211 2354 2347 2203 2202 2503 2209 2504 2204 2203 2497 2505 2355 2503 2205 2204 2498 2355 2506 2213 2205 2349 2206 2506 2357 2074 2208 2206 2351 2507 2359 2356 2207 2208 2353 2508 2360 2507 2207 2352 2354 2361 2508 2509 2354 2211 2210 2361 2510 2217 2210 2209 2212 2510 2219 2364 2212 2355 2213 2511 2218 2362 2213 2506 2074 2512 2365 2511 2074 2357 2072 2513 2366 2512 2072 2359 2215 2514 2367 2513 2360 2216 2215 2515 2368 2514 2361 2217 2216 2516 2369 2515 2510 2364 2217 2517 2370 2516 2219 2080 2364 2518 2519 2373 2218 2079 2080 2371 2520 2227 2365 2221 2079 2520 2229 2374 2221 2366 2222 2521 2228 2372 2222 2367 2223 2522 2375 2521 2223 2368 2224 2523 2376 2522 2224 2369 2225 2524 2377 2523 2370 2226 2225 92 95 97 2371 2227 2226 94 93 2234 2520 2374 2227 93 2379 2236 2374 2229 2090 2525 2380 2378 2090 2228 2089 2526 2527 2528 2089 2375 2231 2381 1812 90 2232 2231 2376 1813 2528 109 2233 2232 2377 2243 2387 2242 2386 2382 2242 2102 89 91 2234 93 2236 2382 2529 2383 2235 2236 2379 2383 2530 2384 2235 2380 2237 2531 2385 2384 90 2237 2381 2385 2532 2388 1812 91 90 104 2386 105 2243 1813 2387 2393 2249 2533 2389 2393 2534 2388 2244 2385 2529 2382 2386 2535 2390 2534 2383 2529 2530 2391 2535 2536 2384 2530 2531 2537 2392 2536 2532 2385 2531 2534 2393 2098 2533 2249 2388 1956 2399 2252 2252 2395 2397 2392 1955 2248 2389 2534 2390 2397 2538 2398 2390 2535 2391 2398 2539 2401 2391 2536 2392 2400 2540 2403 1956 2537 2399 2402 2403 2541 2541 2404 2255 2398 2401 2253 2538 2397 2395 2403 2542 2541 2539 2398 2538 2402 2255 2114 2400 2401 2540 2256 2405 2407 2405 2543 2544 2114 2255 2115 2255 2402 2541 1690 2406 2545 2258 2407 2406 2257 2256 2407 2406 2407 2546 2118 2406 1690 1689 1691 2262 1686 1685 2408 1687 2547 1685 2262 2409 2263 1685 2548 2409 2549 2550 1843 2549 1842 2548 2550 2551 1979 1842 2549 1843 2265 2124 2552 1979 1843 2550 2553 2554 2555 1979 2551 2124 2556 2554 2557 2552 2124 2551 2129 2558 2420 2266 2265 2552 2127 2420 2422 2264 2266 2268 2422 2271 2131 2558 2267 2268 2559 2560 2561 2267 2558 2129 2425 2274 2423 2129 2420 2127 2275 2274 2424 2127 2422 2131 2562 2563 2564 2271 2270 2131 2279 2277 2427 2272 2423 2270 705 2279 558 2272 2425 2423 567 566 708 2425 2424 2274 566 2565 2429 2276 2275 2424 2429 2430 2281 2277 2276 2427 2430 2432 2140 558 2279 2427 2432 2566 2433 705 558 557 2433 2567 2434 705 557 698 2437 2568 2569 698 567 708 2435 2436 2285 708 566 2280 2436 2287 2438 2280 2429 2281 2287 2570 2286 2281 2430 2140 2286 2571 2439 2140 2432 2138 2439 2572 2440 2138 2433 2283 2440 2573 2441 2283 2434 2284 2441 2574 2442 2435 2285 2284 2442 2575 2443 2436 2438 2285 2446 2576 2577 2287 2146 2438 2444 2445 2294 2286 2145 2146 2445 2447 2295 2439 2289 2145 2447 2297 2449 2289 2440 2290 2297 2578 2296 2290 2441 2291 2296 2579 2450 2291 2442 2292 2450 2580 2451 2292 2443 2293 2451 2581 2452 2444 2294 2293 2455 2582 2583 2445 2295 2294 2453 2454 2302 2447 2449 2295 2454 2456 2304 2449 2297 2156 2456 2584 2457 2156 2296 2155 2457 2585 2458 2155 2450 2299 2458 2308 2459 2300 2299 2451 2308 2586 2306 2301 2300 2452 2306 2587 2460 2301 2453 2302 2460 2462 2168 2304 2302 2454 2462 2588 2461 2303 2304 2456 2461 2313 2463 2457 2305 2303 2313 2589 2311 2459 2305 2458 2311 2316 2464 2308 2307 2459 2316 2590 2314 2306 2309 2307 2314 2466 2319 2460 2168 2309 2591 2592 2593 2462 2166 2168 2465 2594 2467 2461 2463 2166 2594 2468 2321 2463 2313 2312 2595 2596 2597 2311 2464 2312 2469 2598 2470 2464 2316 2315 2598 2599 2471 2315 2314 2319 2599 2600 2472 2318 2319 2466 2600 2601 2473 2467 2318 2465 2601 2179 2474 2321 2467 2594 2602 2180 2603 2321 2468 2322 2180 2602 2475 2470 2322 2469 2602 2604 2476 2471 2470 2598 2604 2605 2477 2472 2471 2599 2605 2606 2478 2473 2472 2600 2606 2607 2479 2474 2473 2601 2607 2608 2480 2178 2474 2179 2608 2609 2481 2180 2475 2178 2609 2610 2482 2602 2476 2475 2610 2611 2483 2604 2477 2476 2611 2612 2484 2605 2478 2477 2612 2613 2485 2606 2479 2478 2613 2614 2486 2607 2480 2479 2614 2615 2341 2608 2481 2480 2615 2487 2342 2482 2481 2609 2487 2489 2490 2483 2482 2610 2489 2616 2491 2484 2483 2611 2616 2493 2199 2485 2484 2612 2493 2617 2492 2485 2613 2486 2492 2618 2346 2486 2614 2341 2618 2494 2347 2615 2342 2341 2494 2496 2497 2342 2487 2490 2496 2350 2498 2490 2489 2491 2350 2619 2348 2616 2199 2491 2348 2499 2351 2493 2197 2199 2499 2501 2353 2492 2346 2197 2620 2621 2622 2347 2346 2618 2502 2504 2211 2494 2497 2347 2504 2620 2503 2498 2497 2496 2623 2624 2625 2349 2498 2350 2505 2358 2506 2351 2349 2348 2358 2623 2356 2353 2351 2499 2356 2626 2507 2352 2353 2501 2507 2627 2508 2352 2502 2211 2628 2629 2630 2211 2504 2209 2509 2363 2510 2355 2209 2503 2363 2628 2362 2355 2505 2506 2362 2631 2511 2506 2358 2357 2511 2632 2512 2357 2356 2359 2512 2633 2513 2359 2507 2360 2513 2634 2514 2360 2508 2361 2514 2635 2515 2509 2510 2361 2636 2637 2638 2363 2219 2510 2519 2636 2639 2362 2218 2219 2517 2518 2371 2511 2365 2218 2518 2373 2520 2365 2512 2366 2373 2640 2372 2366 2513 2367 2372 2641 2521 2367 2514 2368 2521 2642 2522 2368 2515 2369 2522 2643 2523 2369 2516 2370 2523 2644 2524 2517 2371 2370 2524 92 94 2518 2520 2371 92 97 93 2520 2373 2229 97 96 2378 2229 2372 2228 2378 2645 2525 2228 2521 2375 2525 2526 2381 2375 2522 2376 2526 2528 1812 2377 2376 2523 2528 2646 109 2377 2524 94 2387 105 2386 104 2529 2386 2243 91 1813 93 97 2379 2647 2530 2529 2379 2378 2380 2530 2648 2531 2380 2525 2381 2531 2649 2532 1812 2381 2526 2532 2650 2533 1813 1812 2528 104 103 102 109 105 2387 2098 2393 2651 2534 2098 81 2533 2388 2532 2529 104 2647 2535 81 2652 2648 2530 2647 2653 2536 2652 2649 2531 2648 2654 2537 2653 2532 2649 2650 2655 2656 2657 2651 2393 2533 2399 2396 2395 2394 2538 2395 2537 1956 2392 81 2535 2534 2538 2656 2539 2535 2652 2536 2539 2655 2540 2536 2653 2537 2658 2394 2659 2396 2399 2654 2542 2403 2660 2661 2541 2542 2539 2540 2401 2394 2656 2538 2543 2404 2661 2656 2655 2539 2661 2542 2662 2540 2660 2403 2405 2544 2546 2663 2664 2545 2255 2404 2256 2404 2541 2661 2408 2545 2664 2406 2546 2545 2407 2405 2546 2546 2663 2545 1690 2545 2408 1691 1685 2409 2665 2547 1687 2665 2411 2547 2409 2548 1842 2547 2666 2548 2550 2667 2413 2667 2549 2666 2413 2417 2551 2550 2549 2667 2555 2266 2552 2550 2413 2551 2268 2266 2554 2417 2552 2551 2558 2268 2556 2417 2555 2552 2418 2556 2668 2554 2266 2555 2669 2670 2671 2556 2268 2554 2421 2559 2271 2558 2556 2418 2559 2672 2272 2420 2558 2418 2673 2674 2675 2420 2419 2422 2563 2276 2424 2421 2271 2422 2427 2276 2562 2271 2559 2272 2676 2677 2678 2672 2425 2272 2676 685 667 2672 2426 2425 565 2679 2565 2426 2563 2424 2565 2680 2681 2562 2276 2563 2430 2429 2681 2428 2427 2562 2431 2682 2566 558 2428 556 2566 2683 2567 666 557 556 2567 2684 2685 567 666 565 2435 2434 2685 566 565 2565 2436 2435 2568 2681 2429 2565 2437 2686 2570 2430 2681 2431 2570 2687 2571 2432 2431 2566 2571 2688 2572 2433 2566 2567 2572 2689 2573 2434 2567 2685 2573 2690 2574 2435 2685 2568 2691 2692 2693 2568 2437 2436 2577 2691 2694 2437 2570 2287 2444 2443 2695 2570 2571 2286 2445 2444 2576 2439 2571 2572 2446 2696 2448 2440 2572 2573 2448 2697 2578 2441 2573 2574 2578 2698 2579 2442 2574 2575 2579 2699 2580 2443 2575 2695 2580 2700 2581 2444 2695 2576 2581 2701 2702 2576 2446 2445 2453 2452 2702 2446 2448 2447 2454 2453 2582 2297 2448 2578 2455 2703 2584 2296 2578 2579 2584 2704 2585 2450 2579 2580 2705 2706 2707 2451 2580 2581 2308 2458 2708 2702 2452 2581 2586 2705 2587 2582 2453 2702 2709 2710 2711 2454 2582 2455 2462 2460 2712 2584 2456 2455 2588 2709 2713 2585 2457 2584 2313 2461 2713 2585 2708 2458 2589 2714 2715 2586 2308 2708 2316 2311 2715 2586 2587 2306 2590 2716 2717 2587 2712 2460 2466 2314 2717 2712 2588 2462 2465 2466 2718 2588 2713 2461 2594 2465 2592 2713 2589 2313 2468 2594 2591 2311 2589 2715 2469 2468 2719 2715 2590 2316 2598 2469 2595 2314 2590 2717 2599 2598 2597 2466 2717 2718 2600 2599 2720 2592 2465 2718 2601 2600 2721 2591 2594 2592 2179 2601 2722 2719 2468 2591 2180 2179 2723 2595 2469 2719 2724 2725 2726 2597 2598 2595 2604 2602 2727 2720 2599 2597 2605 2604 2725 2721 2600 2720 2606 2605 2724 2722 2601 2721 2607 2728 2608 2723 2179 2722 2608 2729 2609 2723 2603 2180 2730 2731 2732 2603 2727 2602 2610 2609 2733 2727 2725 2604 2611 2610 2734 2725 2724 2605 2612 2611 2735 2724 2736 2606 2613 2612 2737 2736 2728 2607 2614 2613 2738 2728 2729 2608 2615 2614 2739 2729 2733 2609 2487 2615 2740 2733 2734 2610 2488 2741 2742 2735 2611 2734 2616 2489 2742 2737 2612 2735 2493 2616 2743 2738 2613 2737 2744 2745 2746 2614 2738 2739 2618 2492 2747 2615 2739 2740 2494 2618 2748 2487 2740 2488 2495 2749 2750 2489 2488 2742 2350 2496 2750 2616 2742 2743 2619 2751 2752 2743 2617 2493 2499 2348 2752 2492 2617 2747 2500 2753 2754 2747 2748 2618 2502 2501 2754 2495 2494 2748 2504 2502 2621 2495 2750 2496 2620 2755 2756 2619 2350 2750 2505 2503 2756 2752 2348 2619 2358 2505 2624 2500 2499 2752 2623 2757 2626 2754 2501 2500 2626 2758 2627 2621 2502 2754 2630 2759 2760 2504 2621 2620 2509 2508 2761 2503 2620 2756 2363 2509 2629 2624 2505 2756 2628 2762 2631 2358 2624 2623 2631 2763 2632 2356 2623 2626 2632 2764 2633 2507 2626 2627 2633 2765 2634 2508 2627 2761 2634 2766 2635 2509 2761 2629 2638 2767 2768 2629 2628 2363 2516 2515 2769 2628 2631 2362 2517 2516 2637 2631 2632 2511 2518 2517 2636 2512 2632 2633 2519 2770 2640 2513 2633 2634 2640 2771 2641 2514 2634 2635 2641 2772 2642 2515 2635 2769 2642 2773 2643 2516 2769 2637 2643 2774 2644 2517 2637 2636 2775 2776 2777 2636 2519 2518 92 2524 2778 2373 2519 2640 95 2775 96 2372 2640 2641 96 2779 2645 2521 2641 2642 2645 2780 2781 2522 2642 2643 2526 2525 2781 2644 2523 2643 2527 2782 2646 2778 2524 2644 2646 2783 110 92 2778 95 2784 123 2785 102 2647 104 2387 1813 109 2378 96 2645 2647 2786 2648 2525 2645 2781 2787 2649 2648 2527 2526 2781 2649 2788 2650 2646 2528 2527 2650 2789 2651 2646 110 109 112 102 101 105 110 103 82 2098 2790 2791 2792 2793 2651 2533 2650 2647 102 2786 2652 80 2794 2648 2786 2787 2653 2794 2795 2788 2649 2787 2791 2654 2795 2789 2650 2788 80 82 2796 2790 2098 2651 2396 2659 2394 2394 2658 2656 2654 2399 2537 80 2652 81 2797 2798 2662 2794 2653 2652 2655 2799 2660 2653 2795 2654 2658 2800 2801 2396 2791 2659 2662 2542 2802 2661 2662 2803 2655 2660 2540 2657 2656 2658 2804 2543 2803 2657 2799 2655 2805 2663 2544 2660 2802 2542 2805 2806 2807 2808 2664 2809 2404 2543 2405 2543 2661 2803 2805 2544 2804 1687 1686 2664 2546 2544 2663 2663 2809 2664 2408 2664 1686 1685 2547 2548 2412 2411 2665 2810 2811 2812 2548 2666 2549 2411 2813 2666 2812 2814 2815 2813 2414 2667 2816 2817 2818 2413 2667 2414 2819 2820 2816 2413 2415 2417 2821 2822 2823 2417 2416 2555 2824 2825 2826 2553 2555 2416 2419 2827 2670 2557 2554 2553 2670 2560 2421 2668 2556 2557 2828 2829 2830 2827 2418 2668 2561 2673 2672 2418 2827 2419 2831 2563 2426 2419 2670 2421 2832 2564 2831 2421 2560 2559 2677 2428 2562 2561 2672 2559 556 2428 2676 2672 2673 2426 666 670 565 2426 2673 2831 700 2680 2679 2564 2563 2831 2833 2834 2835 2677 2562 2564 2681 2836 2431 2676 2428 2677 2835 2683 2682 556 2676 667 2837 2684 2683 670 666 667 2838 2839 2840 565 670 2679 2685 2841 2568 2680 2565 2679 2569 2840 2686 2836 2681 2680 2842 2687 2686 2682 2431 2836 2843 2688 2687 2566 2682 2683 2844 2689 2688 2567 2683 2684 2845 2690 2689 2685 2684 2841 2846 2847 2693 2568 2841 2569 2574 2848 2575 2569 2686 2437 2575 2692 2695 2686 2687 2570 2695 2691 2576 2571 2687 2688 2577 2849 2696 2572 2688 2689 2850 2697 2696 2573 2689 2690 2851 2698 2697 2574 2690 2848 2852 2699 2698 2575 2848 2692 2853 2700 2699 2695 2692 2691 2854 2701 2700 2576 2691 2577 2855 2856 2857 2446 2577 2696 2702 2858 2582 2448 2696 2697 2583 2857 2703 2578 2697 2698 2859 2704 2703 2579 2698 2699 2860 2861 2704 2580 2699 2700 2585 2861 2708 2581 2700 2701 2708 2706 2586 2858 2702 2701 2862 2863 2705 2583 2582 2858 2587 2863 2712 2455 2583 2703 2712 2710 2588 2704 2584 2703 2864 2865 2866 2861 2585 2704 2713 2867 2589 2861 2706 2708 2866 2868 2714 2705 2586 2706 2715 2868 2590 2705 2863 2587 2869 2870 2871 2863 2710 2712 2717 2872 2718 2710 2709 2588 2718 2873 2592 2713 2709 2867 2593 2874 2875 2867 2714 2589 2591 2875 2719 2715 2714 2868 2719 2876 2595 2590 2868 2716 2877 2878 2879 2717 2716 2872 2597 2880 2720 2718 2872 2873 2720 2881 2721 2593 2592 2873 2721 2882 2722 2875 2591 2593 2722 2883 2723 2876 2719 2875 2723 2884 2603 2876 2596 2595 2727 2603 2885 2596 2880 2597 2725 2727 2886 2881 2720 2880 2887 2736 2724 2882 2721 2881 2888 2728 2736 2883 2722 2882 2607 2606 2736 2883 2884 2723 2729 2728 2889 2603 2884 2885 2733 2729 2890 2727 2885 2886 2734 2733 2891 2886 2726 2725 2734 2892 2735 2726 2887 2724 2735 2893 2737 2887 2888 2736 2737 2894 2738 2888 2889 2728 2738 2895 2739 2889 2890 2729 2739 2896 2740 2890 2891 2733 2740 2897 2488 2891 2892 2734 2898 2899 2900 2893 2735 2892 2742 2901 2743 2894 2737 2893 2743 2902 2617 2895 2738 2894 2617 2903 2747 2739 2895 2896 2747 2745 2748 2740 2896 2897 2748 2744 2495 2488 2897 2741 2904 2905 2749 2742 2741 2901 2750 2905 2619 2743 2901 2902 2906 2907 2751 2902 2903 2617 2752 2907 2500 2747 2903 2745 2908 2909 2753 2745 2744 2748 2754 2909 2621 2744 2749 2495 2622 2910 2755 2749 2905 2750 2911 2912 2755 2751 2619 2905 2756 2912 2624 2751 2907 2752 2625 2913 2757 2753 2500 2907 2914 2758 2757 2909 2754 2753 2915 2916 2760 2622 2621 2909 2627 2917 2761 2620 2622 2755 2761 2759 2629 2912 2756 2755 2630 2918 2762 2625 2624 2912 2919 2763 2762 2623 2625 2757 2920 2764 2763 2626 2757 2758 2921 2765 2764 2627 2758 2917 2922 2923 2924 2761 2917 2759 2924 2925 2768 2629 2759 2630 2635 2926 2769 2630 2762 2628 2769 2767 2637 2631 2762 2763 2638 2927 2639 2632 2763 2764 2639 2928 2770 2633 2764 2765 2929 2771 2770 2634 2765 2766 2930 2772 2771 2635 2766 2926 2931 2773 2772 2769 2926 2767 2932 2774 2773 2637 2767 2638 2933 2934 2777 2636 2638 2639 2644 2935 2778 2639 2770 2519 2778 2776 95 2640 2770 2771 2936 2779 2775 2641 2771 2772 2937 2780 2779 2642 2772 2773 2938 2939 2940 2643 2773 2774 2781 2941 2527 2935 2644 2774 2782 2940 2783 2776 2778 2935 2942 2943 111 2775 95 2776 110 2944 103 2775 2779 96 112 2786 102 2645 2779 2780 134 2787 2786 2941 2781 2780 2787 2945 2788 2782 2527 2941 2788 2946 2789 2646 2782 2783 2789 2947 2790 2944 110 2783 119 112 111 101 103 2944 2796 82 2948 80 2796 2949 2790 2651 2789 2786 112 134 2950 2794 2949 2945 2787 134 2792 2795 2950 2788 2945 2946 2801 2951 2952 2947 2789 2946 2949 2796 2953 2948 82 2790 2659 2800 2658 2801 2657 2658 2791 2396 2654 80 2949 2794 2657 2952 2799 2794 2950 2795 2799 2954 2802 2795 2792 2791 2951 2801 2955 2659 2793 2800 2803 2798 2956 2956 2806 2804 2799 2802 2660 2952 2657 2801 2798 2957 2956 2954 2799 2952 2807 2809 2805 2802 2797 2662 2662 2798 2803 2807 2958 2959 2543 2804 2544 2804 2803 2956 2808 2960 2961 2808 1687 2664 2663 2805 2809 2808 2809 2960 2665 1687 2808 2547 2411 2666 2261 2410 2412 2260 2410 2261 2666 2813 2667 2410 2962 2813 2963 2817 2415 2963 2414 2962 2817 2820 2416 2414 2963 2415 2823 2557 2553 2415 2817 2416 2668 2557 2822 2820 2553 2416 2827 2668 2964 2820 2823 2553 2965 2825 2966 2822 2557 2823 2560 2669 2829 2964 2668 2822 2829 2674 2561 2671 2827 2964 2967 2968 2969 2827 2671 2670 2970 2969 2971 2670 2669 2560 2972 2677 2564 2560 2829 2561 2973 2678 2972 2674 2673 2561 664 2974 676 2673 2675 2831 670 701 2679 2675 2832 2831 2975 2976 700 2832 2972 2564 2680 2976 2836 2678 2677 2972 2836 2833 2682 685 2676 2678 2835 2977 2837 671 667 685 2978 2979 2839 701 670 671 2684 2980 2841 2679 701 700 2841 2838 2569 2976 2680 700 2840 2981 2842 2833 2836 2976 2982 2843 2842 2835 2682 2833 2983 2844 2843 2683 2835 2837 2984 2985 2986 2684 2837 2980 2986 2987 2847 2841 2980 2838 2690 2988 2848 2569 2838 2840 2848 2846 2692 2686 2840 2842 2693 2989 2694 2687 2842 2843 2694 2990 2849 2688 2843 2844 2849 2991 2850 2689 2844 2845 2850 2992 2851 2690 2845 2988 2993 2852 2851 2848 2988 2846 2994 2853 2852 2692 2846 2693 2995 2854 2853 2691 2693 2694 2996 2997 2856 2577 2694 2849 2701 2998 2858 2696 2849 2850 2858 2855 2583 2697 2850 2851 2857 2999 2859 2698 2851 2852 3000 2860 2859 2699 2852 2853 3001 3002 3003 2700 2853 2854 2861 3004 2706 2998 2701 2854 2707 3003 2862 2855 2858 2998 3005 3006 2862 2857 2583 2855 2863 3006 2710 2859 2703 2857 2711 3007 3008 2860 2704 2859 2709 3008 2867 3004 2861 2860 2867 2864 2714 3004 2707 2706 3009 3010 3011 2862 2705 2707 2868 3012 2716 2862 3006 2863 2716 3013 2872 3006 2711 2710 2872 2869 2873 2711 3008 2709 2873 2871 2593 2867 3008 2864 2874 3014 3015 2864 2866 2714 2875 3015 2876 2868 2866 3012 2876 3016 2596 2716 3012 3013 2880 2596 3017 2872 3013 2869 2880 2878 2881 2873 2869 2871 2881 2877 2882 2874 2593 2871 2882 3018 2883 3015 2875 2874 2883 3019 2884 3016 2876 3015 2884 3020 2885 3016 3017 2596 2886 2885 3021 3017 2878 2880 2726 2886 3022 2878 2877 2881 2887 2726 3023 2877 3018 2882 2888 2887 3024 3018 3019 2883 2889 2888 3025 3019 3020 2884 2890 2889 3026 2885 3020 3021 2891 2890 3027 2886 3021 3022 2892 2891 3028 2726 3022 3023 2893 2892 3029 3023 3024 2887 2893 3030 2894 3024 3025 2888 2894 3031 2895 3025 3026 2889 2895 3032 2896 3026 3027 2890 2896 3033 2897 3027 3028 2891 2897 3034 2741 3028 3029 2892 2741 3035 2901 3030 2893 3029 2901 2898 2902 3031 2894 3030 2902 2900 2903 3032 2895 3031 2903 3036 2745 3033 2896 3032 2746 3037 3038 2897 3033 3034 2744 3038 2749 2741 3034 3035 3039 3040 3041 2901 3035 2898 2905 3042 2751 2902 2898 2900 3043 3044 3045 2900 3036 2903 2907 3046 2753 2745 3036 2746 3045 3047 2908 2746 3038 2744 2909 3047 2622 3038 2904 2749 2910 3048 2911 2904 3042 2905 3049 3050 3051 2906 2751 3042 2912 3052 2625 2906 3046 2907 2913 3051 2914 2908 2753 3046 3053 3054 2914 3047 2909 2908 2758 3054 2917 2910 2622 3047 2917 2915 2759 2911 2755 2910 2760 3055 2918 3052 2912 2911 2918 3056 2919 2913 2625 3052 3057 2920 2919 2757 2913 2914 3058 2921 2920 2758 2914 3054 3059 3060 2923 2917 3054 2915 2765 3061 2766 2759 2915 2760 2766 2922 2926 2630 2760 2918 2926 2924 2767 2762 2918 2919 2768 3062 2927 2763 2919 2920 2927 3063 2928 2764 2920 2921 2928 3064 2929 2765 2921 3061 3065 2930 2929 2766 3061 2922 3066 2931 2930 2926 2922 2924 3067 2932 2931 2767 2924 2768 3068 3069 2934 2638 2768 2927 2774 3070 2935 2639 2927 2928 2935 2933 2776 2770 2928 2929 2777 3071 2936 2771 2929 2930 2936 3072 2937 2772 2930 2931 3073 3074 2937 2773 2931 2932 2780 3074 2941 2774 2932 3070 2941 2938 2782 2933 2935 3070 2940 3075 3076 2777 2776 2933 2783 3076 2944 2936 2775 2777 2944 2942 101 2937 2779 2936 3077 119 111 2780 2937 3074 121 2945 134 2938 2941 3074 3078 2946 2945 2940 2782 2938 2946 3079 2947 3076 2783 2940 2947 3080 2948 2942 2944 3076 119 3077 120 101 2942 111 2953 2796 3081 2949 2953 3082 2948 2790 2947 134 119 121 2950 3082 98 2945 121 3078 3083 2792 98 3079 2946 3078 3084 2793 3083 3080 2947 3079 3085 3082 2953 2948 3081 2796 2800 2955 2801 3086 3087 3088 2793 2659 2791 3082 2950 2949 3089 2954 2952 2950 98 2792 2954 3090 2797 2792 3083 2793 2951 3091 3087 2800 3084 2955 2957 2798 3092 3093 2956 2957 2954 2797 2802 3089 2952 2951 2958 2806 3093 3089 3090 2954 3093 2957 3094 2797 3092 2798 2807 2959 2960 2959 3095 3096 2804 2806 2805 2806 2956 3093 2412 2961 3097 2961 2665 2808 2809 2807 2960 2961 2960 3098 2412 2665 2961 2410 2813 2411 3099 2260 2259 3099 2814 2260 2813 2962 2414 2260 3100 2962 3101 3102 3103 2818 2963 3100 3104 3105 3106 2817 2963 2818 3107 3108 3104 2817 2816 2820 2826 2964 2822 2820 2819 2823 2671 2964 2825 2821 2823 2819 2669 2965 2830 2821 2826 2822 3109 3110 3111 2825 2964 2826 2828 2967 2674 2671 2825 2965 2967 2970 2675 2671 2965 2669 3112 2972 2832 2669 2830 2829 3113 3114 3115 2828 2674 2829 685 2678 2974 2967 2675 2674 671 663 701 2675 2970 2832 699 3116 2975 2970 3112 2832 3117 3118 3119 2973 2972 3112 2976 3120 2833 2974 2678 2973 2834 3119 2977 664 685 2974 2977 3121 3122 663 671 664 2837 3122 2980 699 701 663 2980 2978 2838 2975 700 699 2839 3123 2981 3120 2976 2975 2981 3124 2982 2834 2833 3120 3125 2983 2982 2977 2835 2834 3126 3127 2985 2837 2977 3122 2844 3128 2845 2980 3122 2978 2845 2984 2988 2838 2978 2839 2988 2986 2846 2981 2840 2839 2847 3129 2989 2842 2981 2982 2989 3130 2990 2843 2982 2983 2990 3131 2991 2844 2983 3128 2991 3132 2992 2845 3128 2984 2992 3133 2993 2988 2984 2986 3134 2994 2993 2846 2986 2847 3135 2995 2994 2693 2847 2989 3136 3137 2997 2694 2989 2990 2854 3138 2998 2849 2990 2991 2998 2996 2855 2992 2850 2991 2856 3139 2999 2851 2992 2993 2999 3140 3000 2852 2993 2994 3141 3142 3000 2853 2994 2995 2860 3142 3004 2854 2995 3138 3004 3001 2707 2996 2998 3138 3003 3143 3005 2856 2855 2996 3144 3145 3146 2999 2857 2856 3006 3147 2711 3000 2859 2999 3007 3146 3148 3142 2860 3000 3008 3148 2864 3142 3001 3004 2865 3149 3150 3001 3003 2707 2866 3150 3012 3005 2862 3003 3012 3009 3013 3005 3147 3006 3013 3011 2869 2711 3147 3007 2870 3151 3152 3007 3148 3008 2871 3152 2874 2864 3148 2865 3153 3154 3155 2865 3150 2866 3015 3156 3016 3012 3150 3009 3016 3157 3017 3013 3009 3011 2878 3017 3158 2870 2869 3011 2879 3159 3160 2871 2870 3152 2877 3160 3018 3014 2874 3152 3018 3161 3019 3156 3015 3014 3019 3162 3020 3157 3016 3156 3020 3163 3021 3157 3158 3017 3022 3021 3164 3158 2879 2878 3023 3022 3165 2879 3160 2877 3024 3023 3166 3160 3161 3018 3025 3024 3167 3161 3162 3019 3026 3025 3168 3162 3163 3020 3027 3026 3169 3021 3163 3164 3028 3027 3170 3022 3164 3165 3029 3028 3171 3023 3165 3166 3030 3029 3172 3024 3166 3167 3031 3030 3173 3167 3168 3025 3031 3174 3032 3168 3169 3026 3032 3175 3033 3169 3170 3027 3033 3176 3034 3170 3171 3028 3034 3177 3035 3171 3172 3029 3035 3178 2898 3172 3173 3030 2899 3179 3180 3174 3031 3173 2900 3180 3036 3175 3032 3174 3036 3181 2746 3176 3033 3175 3037 3182 3183 3034 3176 3177 3038 3183 2904 3035 3177 3178 2904 3184 3042 2898 3178 2899 3042 3039 2906 2900 2899 3180 2906 3041 3046 3180 3181 3036 3046 3043 2908 2746 3181 3037 3185 3186 3187 3037 3183 3038 3047 3188 2910 3183 3184 2904 3048 3187 3189 3184 3039 3042 2911 3189 3052 3041 2906 3039 3052 3049 2913 3041 3043 3046 3051 3190 3053 3045 2908 3043 3191 3192 3193 3188 3047 3045 3054 3194 2915 3188 3048 2910 2916 3193 3055 3189 2911 3048 3055 3195 3056 3049 3052 3189 3056 3196 3057 3051 2913 3049 3197 3058 3057 2914 3051 3053 3198 3199 3060 3054 3053 3194 2921 3200 3061 2915 3194 2916 3061 3059 2922 3055 2760 2916 2923 3201 2925 3056 2918 3055 2925 3202 3062 2919 3056 3057 3062 3203 3063 2920 3057 3058 3063 3204 3064 2921 3058 3200 3064 3205 3065 3061 3200 3059 3206 3066 3065 2922 3059 2923 3207 3067 3066 2924 2923 2925 3208 3209 3069 2768 2925 3062 2932 3210 3070 2927 3062 3063 3070 3068 2933 3064 2928 3063 2934 3211 3071 3065 2929 3064 3071 3212 3072 2930 3065 3066 3072 3213 3073 2931 3066 3067 3214 3215 3216 2932 3067 3210 3074 3217 2938 3068 3070 3210 2939 3216 3075 2934 2933 3068 3075 3218 3219 3071 2777 2934 3076 3219 2942 3071 3072 2936 2943 3220 3077 3073 2937 3072 3221 3222 123 3074 3073 3217 121 2784 3078 2939 2938 3217 3078 2785 3079 3075 2940 2939 3223 3080 3079 3219 3076 3075 3080 3224 3081 2943 2942 3219 120 3225 3221 2943 3077 111 3085 2953 3226 99 3082 3085 3081 2948 3080 121 120 2784 107 3227 108 3078 2784 2785 3083 100 3228 3079 2785 3223 3229 3084 3228 3224 3080 3223 99 3085 3227 3226 2953 3081 2955 3091 2951 3087 3089 2951 3084 2800 2793 3082 99 98 3089 3230 3090 98 100 3083 3090 3231 3092 3083 3228 3084 2957 3232 3094 2955 3229 3091 3093 3094 3233 3234 3235 3096 3090 3092 2797 3230 3089 3087 3095 2958 3233 3231 3090 3230 3096 3098 2959 3092 3232 2957 3096 3236 3234 3237 3097 3235 2806 2958 2807 2958 3093 3233 2261 3097 3237 2961 3098 3097 2960 2959 3098 3098 3235 3097 2412 3097 2261 2410 2260 2962 2815 2814 3099 3238 3239 3240 2962 3100 2963 3241 3100 2814 3242 3243 2816 3242 2818 3241 3243 3108 2819 2818 3242 2816 3244 2826 2821 2819 2816 3243 3245 3246 3247 2819 3108 2821 3248 3246 3249 3108 3244 2821 2830 3250 3110 2824 2826 3244 3110 2968 2828 2966 2825 2824 3251 2968 3109 3250 2965 2966 3252 3253 3254 2965 3250 2830 3114 2973 3112 3110 2828 2830 2974 2973 3113 2828 2968 2967 675 3255 551 2970 2967 2969 663 668 699 2971 3112 2970 3116 3256 3257 3114 3112 2971 2975 3257 3120 2973 3114 3113 3120 3117 2834 676 2974 3113 3119 3258 3121 676 665 664 3259 3260 3261 668 663 665 3122 3262 2978 668 3116 699 2979 3259 3123 3257 2975 3116 3123 3263 3124 3117 3120 3257 3124 3264 3125 3119 2834 3117 3265 3266 3127 3121 2977 3119 2983 3267 3128 3122 3121 3262 3128 3126 2984 2979 2978 3262 2985 3268 2987 3123 2839 2979 2987 3269 3129 3124 2981 3123 3129 3270 3130 3125 2982 3124 3130 3271 3131 2983 3125 3267 3131 3272 3132 3128 3267 3126 3132 3273 3133 2984 3126 2985 3133 3274 3134 2986 2985 2987 3275 3276 3277 2847 2987 3129 3277 3278 3137 2989 3129 3130 2995 3279 3138 2990 3130 3131 3138 3136 2996 3132 2991 3131 2997 3280 3139 3133 2992 3132 3139 3281 3140 2993 3133 3134 3140 3282 3141 2994 3134 3135 3283 3284 3285 2995 3135 3279 3142 3286 3001 3136 3138 3279 3002 3285 3143 2997 2996 3136 3143 3287 3288 3139 2856 2997 3005 3288 3147 3140 2999 3139 3147 3144 3007 3141 3000 3140 3146 3289 3290 3286 3142 3141 3148 3290 2865 3286 3002 3001 3149 3291 3292 3002 3143 3003 3150 3292 3009 3143 3288 3005 3010 3293 3294 3288 3144 3147 3011 3294 2870 3007 3144 3146 3151 3295 3296 3146 3290 3148 3152 3296 3014 2865 3290 3149 3156 3014 3297 3149 3292 3150 3156 3154 3157 3009 3292 3010 3157 3153 3158 3011 3010 3294 2879 3158 3298 3151 2870 3294 3299 3300 3301 3152 3151 3296 3160 3302 3161 3297 3014 3296 3161 3303 3162 3154 3156 3297 3162 3304 3163 3153 3157 3154 3163 3305 3164 3153 3298 3158 3165 3164 3306 3298 3159 2879 3166 3165 3307 3159 3302 3160 3167 3166 3308 3302 3303 3161 3168 3167 3309 3303 3304 3162 3169 3168 3310 3304 3305 3163 3170 3169 3311 3164 3305 3306 3171 3170 3312 3165 3306 3307 3172 3171 3313 3166 3307 3308 3173 3172 3314 3167 3308 3309 3174 3173 3315 3168 3309 3310 3175 3174 3316 3310 3311 3169 3175 2730 3176 3311 3312 3170 3176 2732 3177 3312 3313 3171 3177 3317 3178 3313 3314 3172 3178 3318 2899 3314 3315 3173 3319 3320 3321 3316 3174 3315 3180 3322 3181 2730 3175 3316 3181 3323 3037 2732 3176 2730 3324 3325 3326 3177 2732 3317 3183 3327 3184 3178 3317 3318 3184 3328 3039 3179 2899 3318 3040 3329 3330 3180 3179 3322 3041 3330 3043 3181 3322 3323 3044 3331 3332 3037 3323 3182 3045 3332 3188 3182 3327 3183 3188 3185 3048 3327 3328 3184 3187 3333 3334 3328 3040 3039 3189 3334 3049 3040 3330 3041 3050 3335 3190 3330 3044 3043 3190 3336 3337 3332 3045 3044 3053 3337 3194 3185 3188 3332 3194 3191 2916 3185 3187 3048 3193 3338 3195 3334 3189 3187 3195 3339 3196 3050 3049 3334 3196 3340 3197 3190 3051 3050 3341 3342 3199 3053 3190 3337 3058 3343 3200 3194 3337 3191 3200 3198 3059 3193 2916 3191 3060 3344 3201 3195 3055 3193 3201 3345 3202 3196 3056 3195 3202 3346 3203 3057 3196 3197 3203 3347 3204 3058 3197 3343 3204 3348 3205 3200 3343 3198 3205 3349 3206 3059 3198 3060 3206 3350 3207 2923 3060 3201 3351 3352 3209 2925 3201 3202 3067 3353 3210 3062 3202 3203 3210 3208 3068 3204 3063 3203 3069 3354 3211 3205 3064 3204 3211 3355 3212 3206 3065 3205 3212 3356 3213 3066 3206 3207 3213 3357 3358 3067 3207 3353 3073 3358 3217 3210 3353 3208 3217 3214 2939 3069 3068 3208 3216 3359 3218 3211 2934 3069 3360 3361 3362 3212 3071 3211 3219 3363 2943 3212 3213 3072 3220 3360 3225 3358 3073 3213 120 3077 3225 3214 3217 3358 3221 2784 120 2939 3214 3216 2785 116 3223 3218 3075 3216 3223 118 3224 3363 3219 3218 3224 3364 3226 3220 2943 3363 3365 3222 3221 3220 3225 3077 3227 3085 3366 99 3227 107 3226 3081 3224 2784 3221 123 3367 100 107 116 2785 123 3368 3228 3367 118 3223 116 3369 3229 3368 3224 118 3364 3370 3371 3372 3366 3085 3226 3091 3088 3087 3086 3230 3087 3229 2955 3084 99 107 100 3371 3231 3230 100 3367 3228 3231 3370 3232 3228 3368 3229 3373 3086 3374 3088 3091 3369 3375 3094 3376 3377 3233 3375 3231 3232 3092 3371 3230 3086 3236 3095 3377 3371 3370 3231 3377 3375 3378 3376 3094 3232 3094 3375 3233 3234 3379 3380 2958 3095 2959 3095 3233 3377 3237 3381 3382 2259 2261 3237 3098 3096 3235 3237 3235 3381 3099 2259 3237 2260 2814 3100 2810 2812 2815 2811 3102 2812 3100 3241 2818 2812 3383 3241 3243 3384 3104 3384 3242 3383 3385 3386 3387 3243 3242 3384 3247 2824 3244 3243 3104 3108 2966 2824 3246 3108 3107 3244 3250 2966 3248 3107 3247 3244 3388 3389 3390 3246 2824 3247 3391 3392 3393 3248 2966 3246 3251 3252 2969 3250 3248 3111 3252 3394 2971 3250 3111 3110 3395 3396 3397 3110 3109 2968 3255 676 3113 3251 2969 2968 3398 553 674 2971 2969 3252 668 3399 3116 3114 2971 3394 3256 561 3400 3394 3115 3114 3257 3400 3117 3113 3115 3255 3118 3401 3258 676 3255 675 3258 3402 3403 675 669 665 3262 3121 3403 3399 668 669 3262 3260 2979 3399 3256 3116 3259 3404 3263 3256 3400 3257 3263 3405 3264 3118 3117 3400 3406 3266 3407 3258 3119 3118 3267 3125 3408 3403 3121 3258 3267 3265 3126 3260 3262 3403 3127 3409 3268 3259 2979 3260 3268 3410 3269 3263 3123 3259 3269 3411 3270 3264 3124 3263 3270 3412 3271 3408 3125 3264 3271 3413 3272 3267 3408 3265 3272 3414 3273 3126 3265 3127 3273 3415 3274 2985 3127 3268 3416 3276 3417 2987 3268 3269 3134 3418 3135 3129 3269 3270 3135 3275 3279 3130 3270 3271 3279 3277 3136 3272 3131 3271 3137 3419 3280 3273 3132 3272 3280 3420 3281 3274 3133 3273 3281 3421 3282 3418 3134 3274 3422 3284 3423 3135 3418 3275 3141 3424 3286 3279 3275 3277 3286 3283 3002 3137 3136 3277 3285 3425 3287 3280 2997 3137 3426 3427 3428 3281 3139 3280 3288 3429 3144 3281 3282 3140 3145 3426 3289 3424 3141 3282 3430 3431 3432 3283 3286 3424 3290 3433 3149 3283 3285 3002 3291 3430 3434 3285 3287 3143 3292 3434 3010 3287 3429 3288 3293 3435 3436 3429 3145 3144 3294 3436 3151 3146 3145 3289 3437 3438 3439 3289 3433 3290 3296 3440 3297 3149 3433 3291 3154 3297 3441 3292 3291 3434 3155 3442 3443 3010 3434 3293 3153 3443 3298 3294 3293 3436 3159 3298 3444 3295 3151 3436 3302 3159 3445 3296 3295 3440 3302 3300 3303 3441 3297 3440 3303 3299 3304 3155 3154 3441 3304 3446 3305 3443 3153 3155 3305 3447 3306 3443 3444 3298 3307 3306 3448 3444 3445 3159 3308 3307 3449 3445 3300 3302 3309 3308 3450 3300 3299 3303 3310 3309 3451 3299 3446 3304 3311 3310 3452 3446 3447 3305 3312 3311 3453 3306 3447 3448 3313 3312 3454 3307 3448 3449 3314 3313 3455 3308 3449 3450 3315 3314 3456 3309 3450 3451 3316 3315 3457 3310 3451 3452 2730 3316 3458 3311 3452 3453 3459 3460 3461 3453 3454 3312 2732 3462 3317 3454 3455 3313 3317 3463 3318 3455 3456 3314 3318 3464 3179 3456 3457 3315 3322 3179 3465 3458 3316 3457 3322 3320 3323 2731 2730 3458 3323 3319 3182 3462 2732 2731 3327 3182 3466 3317 3462 3463 3327 3325 3328 3464 3318 3463 3328 3324 3040 3465 3179 3464 3329 3467 3468 3322 3465 3320 3330 3468 3044 3323 3320 3319 3331 3469 3470 3182 3319 3466 3332 3470 3185 3327 3466 3325 3186 3471 3333 3328 3325 3324 3472 3473 3474 3324 3329 3040 3334 3475 3050 3329 3468 3330 3335 3472 3336 3468 3331 3044 3476 3477 3478 3470 3332 3331 3337 3479 3191 3470 3186 3185 3192 3476 3338 3186 3333 3187 3338 3480 3339 3475 3334 3333 3339 3481 3340 3335 3050 3475 3342 3482 3483 3336 3190 3335 3197 3484 3343 3337 3336 3479 3343 3341 3198 3192 3191 3479 3199 3485 3344 3338 3193 3192 3344 3486 3345 3339 3195 3338 3345 3487 3346 3340 3196 3339 3346 3488 3347 3197 3340 3484 3347 3489 3348 3343 3484 3341 3348 3490 3349 3198 3341 3199 3491 3492 3493 3060 3199 3344 3352 3492 3494 3201 3344 3345 3207 3495 3353 3202 3345 3346 3353 3351 3208 3347 3203 3346 3209 3496 3354 3348 3204 3347 3354 3497 3355 3349 3205 3348 3355 3498 3356 3350 3206 3349 3356 3499 3357 3207 3350 3495 3500 3501 3502 3353 3495 3351 3358 3503 3214 3209 3208 3351 3215 3500 3359 3354 3069 3209 3359 3504 3505 3355 3211 3354 3363 3218 3505 3356 3212 3355 3363 3361 3220 3356 3357 3213 3360 3506 3365 3503 3358 3357 3221 3225 3365 3503 3215 3214 3222 3507 122 3215 3359 3216 3508 126 128 3359 3505 3218 118 127 3364 3363 3505 3361 3364 3509 3366 3360 3220 3361 3510 3507 3222 3360 3365 3225 108 3227 3511 3512 3513 3514 3366 3226 3364 3222 122 123 3367 106 3515 116 122 117 3516 3368 3515 127 118 117 3517 3369 3516 3509 3364 127 106 108 129 3511 3227 3366 3088 3374 3086 3086 3373 3371 3369 3091 3229 106 3367 107 3376 3370 3518 3367 3515 3368 3519 3520 3521 3368 3516 3369 3373 3513 3512 3088 3517 3374 3378 3375 3522 3377 3378 3521 3370 3376 3232 3372 3371 3373 3379 3236 3521 3518 3370 3372 3521 3378 3519 3376 3522 3375 3234 3380 3381 3380 3523 3524 3095 3236 3096 3236 3377 3521 2815 3382 3525 3382 3099 3237 3235 3234 3381 3382 3381 3526 2815 3099 3382 2812 3241 2814 3103 3102 2811 3527 3528 3529 3241 3383 3242 3102 3530 3383 3531 3527 3532 3105 3384 3530 3106 3533 3107 3104 3384 3105 3534 3535 3387 3107 3104 3106 3536 3537 3538 3107 3533 3247 3111 3248 3389 3245 3247 3533 3109 3388 3392 3249 3246 3245 3392 3253 3251 3389 3248 3249 3539 3540 3541 3111 3389 3388 3254 3395 3394 3111 3388 3109 3542 3255 3115 3109 3392 3251 3543 551 3542 3252 3251 3253 3399 669 3398 3252 3254 3394 3399 559 3256 3394 3395 3115 3544 3545 3546 3395 3542 3115 3118 3400 3547 3542 551 3255 3401 3545 3402 551 553 675 3548 3549 3550 553 3398 669 3260 3403 3551 3398 559 3399 3261 3549 3404 559 561 3256 3404 3552 3405 561 3547 3400 3405 3553 3554 3401 3118 3547 3408 3264 3554 3402 3258 3401 3265 3408 3407 3402 3551 3403 3266 3555 3409 3261 3260 3551 3409 3556 3410 3404 3259 3261 3410 3557 3411 3405 3263 3404 3411 3558 3412 3554 3264 3405 3412 3559 3413 3407 3408 3554 3413 3560 3414 3265 3407 3266 3561 3562 3563 3127 3266 3409 3564 3416 3562 3268 3409 3410 3418 3274 3565 3269 3410 3411 3275 3418 3417 3412 3270 3411 3276 3566 3278 3413 3271 3412 3278 3567 3419 3414 3272 3413 3419 3568 3420 3415 3273 3414 3420 3569 3421 3565 3274 3415 3421 3570 3571 3417 3418 3565 3424 3282 3571 3275 3417 3276 3424 3423 3283 3278 3277 3276 3284 3572 3425 3419 3137 3278 3425 3573 3574 3420 3280 3419 3429 3287 3574 3421 3281 3420 3429 3427 3145 3421 3571 3282 3426 3575 3576 3571 3423 3424 3433 3289 3576 3284 3283 3423 3433 3431 3291 3284 3425 3285 3577 3578 3579 3425 3574 3287 3434 3580 3293 3574 3427 3429 3581 3582 3583 3427 3426 3145 3436 3584 3295 3289 3426 3576 3440 3295 3585 3576 3431 3433 3440 3438 3441 3291 3431 3430 3155 3441 3437 3434 3430 3580 3586 3587 3588 3293 3580 3435 3443 3589 3444 3436 3435 3584 3445 3444 3590 3585 3295 3584 3300 3445 3591 3438 3440 3585 3592 3593 3594 3437 3441 3438 3299 3595 3446 3442 3155 3437 3446 3596 3447 3589 3443 3442 3447 3597 3448 3589 3590 3444 3449 3448 3598 3590 3591 3445 3450 3449 3599 3591 3301 3300 3451 3450 3600 3301 3595 3299 3452 3451 3601 3595 3596 3446 3453 3452 3602 3596 3597 3447 3454 3453 3603 3448 3597 3598 3455 3454 3604 3449 3598 3599 3456 3455 3605 3450 3599 3600 3457 3456 3606 3451 3600 3601 3458 3457 3607 3452 3601 3602 2731 3458 3608 3453 3602 3603 3462 2731 3609 3603 3604 3454 3462 3460 3463 3604 3605 3455 3463 3459 3464 3605 3606 3456 3465 3464 3610 3606 3607 3457 3320 3465 3611 3607 3608 3458 3321 3612 3613 3609 2731 3608 3319 3613 3466 3460 3462 3609 3325 3466 3614 3459 3463 3460 3326 3615 3616 3610 3464 3459 3329 3324 3616 3611 3465 3610 3617 3618 3619 3320 3611 3321 3468 3620 3331 3319 3321 3613 3469 3617 3621 3466 3613 3614 3470 3621 3186 3325 3614 3326 3471 3622 3623 3324 3326 3616 3475 3333 3623 3616 3467 3329 3475 3473 3335 3467 3620 3468 3472 3624 3625 3620 3469 3331 3479 3336 3625 3469 3621 3470 3479 3477 3192 3621 3471 3186 3476 3626 3480 3471 3623 3333 3480 3627 3481 3473 3475 3623 3628 3483 3629 3472 3335 3473 3484 3340 3630 3625 3336 3472 3484 3482 3341 3477 3479 3625 3342 3631 3485 3476 3192 3477 3485 3632 3486 3480 3338 3476 3486 3633 3487 3481 3339 3480 3487 3634 3488 3630 3340 3481 3488 3635 3489 3484 3630 3482 3489 3636 3490 3341 3482 3342 3637 3491 3638 3199 3342 3485 3350 3349 3639 3344 3485 3486 3495 3350 3493 3345 3486 3487 3495 3492 3351 3488 3346 3487 3352 3640 3496 3489 3347 3488 3496 3641 3497 3490 3348 3489 3497 3642 3498 3639 3349 3490 3498 3643 3499 3493 3350 3639 3644 3502 3645 3495 3493 3492 3503 3357 3646 3351 3492 3352 3503 3501 3215 3496 3209 3352 3500 3647 3504 3497 3354 3496 3504 3648 3649 3498 3355 3497 3361 3505 3649 3498 3499 3356 3362 3650 3506 3499 3646 3357 3506 3651 3510 3501 3503 3646 3222 3365 3510 3501 3500 3215 3507 3652 3653 3500 3504 3359 117 122 3653 3504 3649 3505 127 126 3509 3362 3361 3649 3509 125 3511 3362 3506 3360 3507 3654 3652 3510 3365 3506 129 108 3655 106 129 3656 3511 3366 3509 3507 3653 122 3657 3515 3656 128 117 3653 3658 3516 3657 127 128 126 3659 3517 3658 125 3509 126 3656 129 131 3655 108 3511 3374 3513 3373 3512 3372 3373 3517 3088 3369 106 3656 3515 3372 3660 3518 3515 3657 3516 3518 3661 3522 3517 3516 3658 3662 3512 3514 3513 3374 3659 3519 3378 3663 3520 3523 3379 3518 3522 3376 3660 3372 3512 3664 3520 3519 3661 3518 3660 3524 3526 3380 3663 3378 3522 3665 3666 3524 3667 3525 3668 3236 3379 3234 3521 3520 3379 2810 3525 3667 3382 3526 3525 3381 3380 3526 3526 3668 3525 2815 3525 2810 2812 3102 3383 3239 3101 3103 3238 3101 3239 3383 3530 3384 3101 3669 3530 3106 3670 3385 3670 3105 3669 3385 3535 3533 3106 3105 3670 3538 3249 3245 3106 3385 3533 3389 3249 3537 3533 3535 3245 3671 3672 3673 3535 3538 3245 3674 3671 3675 3537 3249 3538 3253 3391 3540 3389 3537 3390 3540 3396 3254 3393 3388 3390 3396 3539 3676 3388 3393 3392 3677 3678 3679 3392 3391 3253 672 678 680 3540 3254 3253 559 3398 673 3254 3396 3395 560 3680 3681 3395 3397 3542 3547 561 3681 3543 3542 3397 3401 3547 3546 3543 552 551 3545 3682 3683 552 674 553 3551 3402 3683 674 673 3398 3261 3551 3550 673 560 559 3549 3684 3552 560 3681 561 3552 3685 3553 3681 3546 3547 3686 3687 3688 3545 3401 3546 3407 3554 3689 3545 3683 3402 3555 3406 3687 3683 3550 3551 3555 3690 3556 3549 3261 3550 3556 3691 3557 3552 3404 3549 3557 3692 3558 3553 3405 3552 3558 3693 3559 3689 3554 3553 3694 3695 3696 3406 3407 3689 3697 3561 3695 3266 3406 3555 3415 3414 3698 3409 3555 3556 3565 3415 3563 3410 3556 3557 3417 3565 3562 3558 3411 3557 3566 3416 3699 3559 3412 3558 3566 3700 3567 3560 3413 3559 3567 3701 3568 3698 3414 3560 3568 3702 3569 3563 3415 3698 3569 3703 3570 3562 3565 3563 3704 3705 3706 3416 3417 3562 3423 3571 3707 3566 3276 3416 3572 3422 3705 3567 3278 3566 3572 3708 3573 3568 3419 3567 3573 3709 3710 3569 3420 3568 3427 3574 3710 3569 3570 3421 3428 3711 3575 3570 3707 3571 3575 3712 3713 3707 3422 3423 3431 3576 3713 3422 3572 3284 3432 3714 3715 3572 3573 3425 3580 3430 3715 3573 3710 3574 3580 3578 3435 3710 3428 3427 3584 3435 3577 3428 3575 3426 3584 3582 3585 3576 3575 3713 3438 3585 3581 3431 3713 3432 3439 3716 3717 3430 3432 3715 3442 3437 3717 3580 3715 3578 3589 3442 3718 3435 3578 3577 3589 3587 3590 3584 3577 3582 3591 3590 3586 3581 3585 3582 3301 3591 3719 3439 3438 3581 3595 3301 3720 3717 3437 3439 3595 3593 3596 3718 3442 3717 3596 3592 3597 3587 3589 3718 3597 3721 3598 3587 3586 3590 3599 3598 3722 3586 3719 3591 3600 3599 3723 3719 3720 3301 3601 3600 3724 3720 3593 3595 3602 3601 3725 3593 3592 3596 3603 3602 3726 3592 3721 3597 3604 3603 3727 3598 3721 3722 3605 3604 3728 3599 3722 3723 3606 3605 3729 3600 3723 3724 3607 3606 3730 3601 3724 3725 3608 3607 3731 3602 3725 3726 3609 3608 3732 3603 3726 3727 3460 3609 3733 3604 3727 3728 3734 3735 3736 3728 3729 3605 3459 3737 3610 3729 3730 3606 3611 3610 3738 3730 3731 3607 3321 3611 3739 3731 3732 3608 3740 3741 3742 3733 3609 3732 3613 3743 3614 3461 3460 3733 3326 3614 3744 3737 3459 3461 3745 3746 3747 3738 3610 3737 3467 3616 3748 3739 3611 3738 3620 3467 3749 3321 3739 3612 3620 3618 3469 3613 3612 3743 3750 3751 3752 3614 3743 3744 3471 3621 3753 3326 3744 3615 3622 3751 3754 3616 3615 3748 3473 3623 3754 3467 3748 3749 3474 3755 3624 3749 3618 3620 3756 3757 3758 3618 3617 3469 3477 3625 3759 3621 3617 3753 3478 3757 3626 3753 3622 3471 3626 3760 3627 3622 3754 3623 3627 3761 3762 3474 3473 3754 3630 3481 3762 3624 3472 3474 3482 3630 3629 3624 3759 3625 3483 3763 3631 3478 3477 3759 3631 3764 3632 3626 3476 3478 3632 3765 3633 3627 3480 3626 3633 3766 3634 3762 3481 3627 3634 3767 3635 3629 3630 3762 3768 3769 3770 3482 3629 3483 3771 3637 3769 3342 3483 3631 3639 3490 3772 3485 3631 3632 3493 3639 3638 3633 3486 3632 3494 3491 3773 3634 3487 3633 3494 3774 3640 3635 3488 3634 3640 3775 3641 3636 3489 3635 3641 3776 3642 3772 3490 3636 3642 3777 3643 3638 3639 3772 3778 3644 3779 3491 3493 3638 3646 3499 3780 3492 3491 3494 3501 3646 3645 3640 3352 3494 3502 3781 3647 3641 3496 3640 3647 3782 3648 3642 3497 3641 3783 3784 3785 3643 3498 3642 3362 3649 3786 3643 3780 3499 3650 3784 3651 3780 3645 3646 3787 3788 3789 3502 3501 3645 3507 3510 3654 3502 3647 3500 3652 3788 3790 3647 3648 3504 128 3653 3790 3649 3648 3786 3791 124 3508 3650 3362 3786 125 133 3655 3650 3651 3506 3652 3789 3788 3651 3654 3510 3792 113 115 3656 131 3793 3655 3511 125 3653 3652 3790 3657 3793 3794 128 3790 3508 3795 3658 3794 124 126 3508 3796 3659 3795 133 125 124 3797 3793 131 130 129 3655 3798 3799 3800 3662 3660 3512 3659 3374 3517 3793 3657 3656 3801 3661 3660 3657 3794 3658 3661 3799 3663 3658 3795 3659 3802 3662 3803 3514 3513 3796 3664 3519 3798 3520 3664 3804 3661 3663 3522 3801 3660 3662 3665 3523 3804 3801 3799 3661 3804 3664 3805 3663 3798 3519 3524 3666 3668 3666 3806 3807 3379 3523 3380 3523 3520 3804 3103 3667 3808 2811 2810 3667 3526 3524 3668 3667 3668 3809 3103 2811 3667 3101 3530 3102 3810 3238 3240 3810 3532 3238 3530 3669 3105 3238 3811 3669 3812 3813 3814 3811 3386 3670 3815 3816 3817 3385 3670 3386 3817 3818 3819 3385 3387 3535 3390 3537 3672 3535 3534 3538 3393 3390 3671 3536 3538 3534 3391 3674 3541 3672 3537 3536 3820 3821 3822 3671 3390 3672 3823 3820 3824 3393 3671 3674 3676 3677 3397 3393 3674 3391 679 552 3543 3541 3540 3391 672 3825 3826 3396 3540 3539 560 673 3826 3397 3396 3676 3680 3827 3828 3397 3677 3543 3546 3681 3828 3543 3677 679 3682 3544 3829 552 679 678 3682 3830 3831 678 672 674 3550 3683 3831 673 672 3826 3684 3548 3832 3826 3680 560 3684 3833 3685 3680 3828 3681 3834 3686 3835 3828 3544 3546 3689 3553 3836 3682 3545 3544 3406 3689 3688 3682 3831 3683 3690 3687 3837 3831 3548 3550 3690 3838 3691 3684 3549 3548 3691 3839 3692 3685 3552 3684 3692 3840 3693 3836 3553 3685 3841 3694 3842 3688 3689 3836 3560 3559 3843 3687 3406 3688 3698 3560 3696 3555 3687 3690 3563 3698 3695 3691 3556 3690 3564 3561 3844 3692 3557 3691 3699 3564 3845 3693 3558 3692 3700 3699 3846 3843 3559 3693 3700 3847 3701 3696 3560 3843 3701 3848 3702 3695 3698 3696 3702 3849 3703 3561 3563 3695 3850 3704 3851 3564 3562 3561 3707 3570 3852 3699 3416 3564 3422 3707 3706 3700 3566 3699 3708 3705 3853 3701 3567 3700 3708 3854 3709 3702 3568 3701 3855 3856 3857 3703 3569 3702 3428 3710 3858 3703 3852 3570 3711 3856 3712 3852 3706 3707 3859 3860 3861 3706 3705 3422 3432 3713 3862 3705 3708 3572 3714 3860 3863 3708 3709 3573 3578 3715 3863 3710 3709 3858 3579 3864 3865 3858 3711 3428 3582 3577 3865 3575 3711 3712 3583 3866 3867 3713 3712 3862 3439 3581 3867 3432 3862 3714 3716 3868 3869 3715 3714 3863 3718 3717 3869 3578 3863 3579 3587 3718 3870 3865 3577 3579 3588 3871 3872 3582 3865 3583 3719 3586 3872 3867 3581 3583 3720 3719 3873 3716 3439 3867 3593 3720 3874 3716 3869 3717 3875 3876 3877 3870 3718 3869 3592 3878 3721 3588 3587 3870 3721 3879 3722 3588 3872 3586 3723 3722 3880 3872 3873 3719 3724 3723 3881 3873 3874 3720 3725 3724 3882 3874 3594 3593 3726 3725 3883 3594 3878 3592 3727 3726 3884 3721 3878 3879 3728 3727 3885 3722 3879 3880 3729 3728 3886 3723 3880 3881 3730 3729 3887 3724 3881 3882 3731 3730 3888 3725 3882 3883 3732 3731 3889 3726 3883 3884 3733 3732 3890 3727 3884 3885 3461 3733 3891 3728 3885 3886 3737 3461 3892 3886 3887 3729 3737 3735 3738 3887 3888 3730 3739 3738 3734 3888 3889 3731 3612 3739 3893 3889 3890 3732 3743 3612 3894 3891 3733 3890 3743 3741 3744 3892 3461 3891 3615 3744 3740 3735 3737 3892 3748 3615 3895 3734 3738 3735 3749 3748 3747 3893 3739 3734 3618 3749 3746 3894 3612 3893 3619 3896 3897 3743 3894 3741 3753 3617 3897 3744 3741 3740 3622 3753 3752 3615 3740 3895 3898 3899 3900 3748 3895 3747 3474 3754 3901 3749 3747 3746 3755 3899 3902 3746 3619 3618 3759 3624 3902 3619 3897 3617 3478 3759 3758 3753 3897 3752 3757 3903 3760 3752 3751 3622 3760 3904 3761 3751 3901 3754 3905 3906 3907 3755 3474 3901 3629 3762 3908 3755 3902 3624 3763 3628 3906 3902 3758 3759 3764 3763 3909 3757 3478 3758 3764 3910 3765 3760 3626 3757 3765 3911 3766 3761 3627 3760 3766 3912 3767 3908 3762 3761 3913 3768 3914 3628 3629 3908 3636 3635 3915 3763 3483 3628 3772 3636 3770 3631 3763 3764 3638 3772 3769 3765 3632 3764 3773 3637 3916 3766 3633 3765 3774 3773 3917 3767 3634 3766 3775 3774 3918 3915 3635 3767 3775 3919 3776 3770 3636 3915 3776 3920 3777 3769 3772 3770 3921 3778 3922 3637 3638 3769 3780 3643 3923 3773 3491 3637 3645 3780 3779 3773 3774 3494 3781 3644 3924 3775 3640 3774 3781 3925 3782 3776 3641 3775 3782 3926 3927 3777 3642 3776 3786 3648 3927 3923 3643 3777 3650 3786 3785 3923 3779 3780 3784 3928 3929 3779 3644 3645 3654 3651 3929 3781 3502 3644 3652 3654 3789 3781 3782 3647 3930 3931 3932 3782 3927 3648 3508 3790 3933 3786 3927 3785 3791 3931 132 3784 3650 3785 133 135 130 3929 3651 3784 3788 3787 3934 3929 3789 3654 3797 131 137 3935 3793 3797 130 3655 133 3790 3788 3933 3936 3794 3935 3933 3791 3508 3795 3936 3937 124 3791 132 3938 3796 3937 135 133 132 3935 3797 3792 137 131 130 3514 3803 3662 3662 3802 3801 3796 3513 3659 3793 3935 3794 3801 3939 3799 3936 3795 3794 3940 3941 3802 3795 3937 3796 3664 3942 3805 3514 3938 3803 3804 3805 3943 3943 3806 3665 3799 3798 3663 3939 3801 3802 3805 3944 3943 3800 3799 3939 3807 3809 3666 3798 3942 3664 3945 3946 3807 3947 3808 3948 3523 3665 3524 3804 3943 3665 3239 3808 3947 3667 3809 3808 3668 3666 3809 3809 3948 3808 3103 3808 3239 3101 3238 3669 3531 3532 3810 3949 3950 3951 3669 3811 3670 3532 3952 3811 3953 3954 3387 3953 3386 3952 3954 3955 3534 3386 3953 3387 3672 3536 3956 3534 3387 3954 3957 3958 3959 3534 3955 3536 3960 3958 3961 3956 3536 3955 3541 3962 3821 3673 3672 3956 3821 3823 3539 3671 3673 3675 3823 3678 3676 3962 3674 3675 3963 3964 3965 3674 3962 3541 3966 546 683 3539 3541 3821 3967 3968 3969 3676 3539 3823 3680 3826 3970 3677 3676 3678 3827 3968 3971 679 3677 3679 3544 3828 3971 679 3679 677 3830 3829 3972 678 677 680 3973 3974 3975 680 3825 672 3548 3831 3976 3826 3825 3970 3833 3832 3974 3970 3827 3680 3833 3977 3978 3827 3971 3828 3836 3685 3978 3971 3829 3544 3688 3836 3835 3829 3830 3682 3837 3686 3979 3830 3976 3831 3838 3837 3980 3976 3832 3548 3838 3981 3839 3833 3684 3832 3839 3982 3840 3978 3685 3833 3983 3841 3984 3835 3836 3978 3843 3693 3985 3686 3688 3835 3696 3843 3842 3686 3837 3687 3697 3694 3986 3838 3690 3837 3844 3697 3987 3839 3691 3838 3845 3844 3988 3840 3692 3839 3846 3845 3989 3985 3693 3840 3847 3846 3990 3842 3843 3985 3847 3991 3848 3694 3696 3842 3848 3992 3849 3697 3695 3694 3993 3850 3994 3844 3561 3697 3852 3703 3995 3845 3564 3844 3706 3852 3851 3845 3846 3699 3853 3704 3996 3847 3700 3846 3854 3853 3997 3848 3701 3847 3854 3998 3999 3849 3702 3848 3858 3709 3999 3995 3703 3849 3711 3858 3857 3995 3851 3852 3856 4000 4001 3851 3704 3706 3862 3712 4001 3704 3853 3705 3714 3862 3861 3853 3854 3708 3860 4002 4003 3854 3999 3709 3579 3863 4003 3858 3999 3857 4004 3864 4005 3857 3856 3711 3583 3865 4004 3712 3856 4001 3866 4006 4007 3862 4001 3861 3716 3867 4007 3714 3861 3860 4008 4009 4010 3863 3860 4003 3870 3869 4011 3864 3579 4003 3588 3870 4012 4004 3865 3864 4013 4014 4015 3583 4004 3866 3873 3872 4016 4007 3867 3866 3874 3873 4017 3868 3716 4007 3594 3874 4018 3868 4011 3869 3878 3594 4019 4012 3870 4011 3878 3876 3879 3871 3588 4012 3880 3879 3875 3871 4016 3872 3881 3880 4020 4016 4017 3873 3882 3881 4021 4017 4018 3874 3883 3882 4022 4018 4019 3594 3884 3883 4023 4019 3876 3878 3885 3884 4024 3879 3876 3875 3886 3885 4025 3880 3875 4020 3887 3886 4026 3881 4020 4021 3888 3887 4027 3882 4021 4022 3889 3888 4028 3883 4022 4023 3890 3889 4029 3884 4023 4024 3891 3890 4030 3885 4024 4025 3892 3891 4031 3886 4025 4026 3735 3892 4032 3887 4026 4027 4033 4034 4035 4027 4028 3888 3893 3734 4036 4028 4029 3889 3894 3893 4037 4029 4030 3890 3741 3894 4038 4030 4031 3891 3742 4039 4040 4032 3892 4031 3895 3740 4040 3736 3735 4032 3747 3895 4041 3736 4036 3734 4042 3745 4043 4037 3893 4036 3619 3746 4042 4038 3894 4037 3896 4044 4045 3741 4038 3742 3752 3897 4045 4040 3740 3742 4046 3750 4047 3895 4040 4041 3901 3751 4046 3747 4041 3745 3755 3901 3900 3746 3745 4042 3899 4048 4049 4042 3896 3619 3758 3902 4049 3897 3896 4045 3903 3756 4050 3752 4045 3750 3904 3903 4051 3750 4046 3751 4052 3905 4053 4046 3900 3901 3908 3761 4054 3899 3755 3900 3628 3908 3907 3899 4049 3902 3909 3906 4055 4049 3756 3758 3910 3909 4056 3756 3903 3757 3910 4057 3911 3904 3760 3903 4058 4059 4060 4054 3761 3904 4061 3913 4059 3907 3908 4054 3915 3767 4062 3906 3628 3907 3770 3915 3914 3906 3909 3763 3771 3768 4063 3910 3764 3909 3916 3771 4064 3911 3765 3910 3917 3916 4065 3912 3766 3911 3918 3917 4066 4062 3767 3912 3919 3918 4067 3914 3915 4062 3919 4068 3920 3768 3770 3914 4069 3921 4070 3771 3769 3768 3923 3777 4071 3916 3637 3771 3779 3923 3922 3916 3917 3773 3924 3778 4072 3917 3918 3774 3925 3924 4073 3919 3775 3918 3925 4074 3926 3920 3776 3919 4075 4076 4077 4071 3777 3920 3785 3927 4078 4071 3922 3923 3928 3783 4076 3922 3778 3779 3928 4079 4080 3778 3924 3644 3789 3929 4080 3924 3925 3781 3934 3787 4081 3925 3926 3782 3933 3788 3934 3926 4078 3927 3791 3933 3932 3785 4078 3783 4082 148 4083 3783 3928 3784 150 4084 155 3928 4080 3929 3934 4081 4085 4080 3787 3789 3792 3797 149 3935 3792 115 137 130 135 3934 3932 3933 4086 3936 115 3932 3931 3791 4087 3937 4086 132 3931 138 4088 3938 4087 135 138 136 4089 4090 4091 149 3797 137 3803 3940 3802 3941 3939 3802 3938 3514 3796 3935 115 3936 3939 4090 3800 3936 4086 3937 3800 4089 3942 3937 4087 3938 4092 3941 4093 3940 3803 4088 3944 3805 4094 4095 3943 3944 3800 3942 3798 3941 4090 3939 3945 3806 4095 4090 4089 3800 4095 3944 4096 3942 4094 3805 3807 3946 3948 3946 4097 4098 3665 3806 3666 3806 3943 4095 3947 4099 4100 3240 3239 3947 3809 3807 3948 3947 3948 4099 3810 3240 3947 3238 3532 3811 3528 3527 3531 3529 3813 3527 3811 3952 3386 3527 4101 3952 3954 4102 3815 4102 3953 4101 3815 3819 3955 3954 3953 4102 3959 3673 3956 3954 3815 3955 3675 3673 3958 3819 3956 3955 3962 3675 3960 3819 3959 3956 4103 4104 4105 3958 3673 3959 4106 4107 4108 3960 3675 3958 3824 3963 3678 3962 3960 3822 3963 4109 3679 3822 3821 3962 3825 680 547 3820 3823 3821 3970 3825 554 3823 3824 3678 3827 3970 3969 3679 3678 3963 4110 4111 4112 3679 4109 677 3829 3971 4113 677 4109 545 4114 3972 4115 680 545 547 3976 3830 4114 547 554 3825 3832 3976 3975 3970 554 3969 3977 3974 4116 3969 3968 3827 4117 4118 4119 3968 4113 3971 3835 3978 4120 3829 4113 3972 3979 3834 4121 3972 4114 3830 3980 3979 4122 4114 3975 3976 3981 3980 4123 3975 3974 3832 3981 4124 3982 3977 3833 3974 4125 4126 4127 4120 3978 3977 3985 3840 4128 3834 3835 4120 3842 3985 3984 3834 3979 3686 3986 3841 4129 3979 3980 3837 3987 3986 4130 3981 3838 3980 3988 3987 4131 3982 3839 3981 3989 3988 4132 4128 3840 3982 3990 3989 4133 3984 3985 4128 3991 3990 4134 3841 3842 3984 3991 4135 3992 3986 3694 3841 4136 4137 4138 3987 3697 3986 3995 3849 4139 3988 3844 3987 3851 3995 3994 3988 3989 3845 3996 3850 4140 3989 3990 3846 3997 3996 4141 3991 3847 3990 3998 3997 4142 3992 3848 3991 4143 4144 4145 4139 3849 3992 3857 3999 4146 4139 3994 3995 4000 3855 4147 3994 3850 3851 4148 4000 4149 3850 3996 3704 3861 4001 4148 3853 3996 3997 4002 3859 4150 3997 3998 3854 4151 4152 4153 3998 4146 3999 3864 4003 4154 3857 4146 3855 4155 4005 4156 3856 3855 4000 3866 4004 4155 4001 4000 4148 4006 4157 4158 3861 4148 3859 3868 4007 4158 3860 3859 4002 4011 3868 4159 4003 4002 4154 4012 4011 4010 4005 3864 4154 3871 4012 4009 4155 4004 4005 4016 3871 4160 3866 4155 4006 4017 4016 4015 4158 4007 4006 4018 4017 4014 4159 3868 4158 4019 4018 4161 4159 4010 4011 3876 4019 4162 4010 4009 4012 4163 4164 4165 4160 3871 4009 4020 3875 4166 4160 4015 4016 4021 4020 4167 4015 4014 4017 4022 4021 4168 4014 4161 4018 4023 4022 4169 4161 4162 4019 4024 4023 4170 4162 3877 3876 4025 4024 4171 3875 3877 4166 4026 4025 4172 4020 4166 4167 4027 4026 4173 4021 4167 4168 4028 4027 4174 4022 4168 4169 4029 4028 4175 4023 4169 4170 4030 4029 4176 4024 4170 4171 4031 4030 4177 4025 4171 4172 4032 4031 4178 4026 4172 4173 3736 4032 4179 4027 4173 4174 4036 3736 4180 4174 4175 4028 4037 4036 4035 4175 4176 4029 4038 4037 4034 4176 4177 4030 3742 4038 4181 4177 4178 4031 4182 4183 4184 4179 4032 4178 4041 4040 4185 4180 3736 4179 3745 4041 4186 4180 4035 4036 4187 4043 4188 4034 4037 4035 3896 4042 4187 4181 4038 4034 4189 4044 4190 3742 4181 4039 3750 4045 4189 4185 4040 4039 4191 4047 4192 4041 4185 4186 3900 4046 4191 4043 3745 4186 4048 3898 4193 4042 4043 4187 4194 4195 4196 3896 4187 4044 3756 4049 4197 4045 4044 4189 4051 4050 4198 3750 4189 4047 4199 4051 4200 4047 4191 4046 4054 3904 4199 4191 3898 3900 3907 4054 4053 3898 4048 3899 4055 3905 4201 4048 4197 4049 4056 4055 4202 4197 4050 3756 4057 4056 4203 4050 4051 3903 4204 4205 4206 4199 3904 4051 3912 3911 4207 4053 4054 4199 4062 3912 4060 3905 3907 4053 3914 4062 4059 3905 4055 3906 4063 3913 4208 4055 4056 3909 4064 4063 4209 4057 3910 4056 4065 4064 4210 4207 3911 4057 4066 4065 4211 4060 3912 4207 4067 4066 4212 4059 4062 4060 4068 4067 4213 3913 3914 4059 4214 4215 4216 4063 3768 3913 4071 3920 4217 4064 3771 4063 3922 4071 4070 4064 4065 3916 4072 3921 4218 4065 4066 3917 4073 4072 4219 4066 4067 3918 4074 4073 4220 4068 3919 4067 4221 4222 4223 4217 3920 4068 4078 3926 4224 4070 4071 4217 3783 4078 4077 4070 3921 3922 4079 4076 4225 3921 4072 3778 4226 4227 4228 4072 4073 3924 3787 4080 4229 4073 4074 3925 4085 4081 4230 4074 4224 3926 3932 3934 4085 4078 4224 4077 4231 3930 141 3783 4077 4076 138 3931 4231 4076 4079 3928 136 138 4083 4079 4229 4080 4085 4230 139 3787 4229 4081 113 3792 4232 4233 4234 4235 149 137 136 4085 3930 3932 4086 114 4236 3930 4231 3931 4237 4087 4236 138 4231 4083 4238 4088 4237 148 136 4083 114 113 4084 4232 3792 149 3940 4093 3941 3941 4092 4090 4088 3803 3938 114 4086 115 4239 4240 4096 4086 4236 4087 4089 4241 4094 4087 4237 4088 4092 4234 4233 3940 4238 4093 4096 3944 4242 4095 4096 4243 4089 4094 3942 4091 4090 4092 4097 3945 4243 4091 4241 4089 4243 4096 4240 4094 4242 3944 3946 4098 4099 4244 4245 4100 3806 3945 3807 3945 4095 4243 3531 4100 4245 4100 3810 3947 3948 3946 4099 4100 4099 4244 3531 3810 4100 3527 3952 3532 3814 3813 3529 4246 4247 4248 3952 4101 3953 3813 4249 4101 4250 4251 4252 4249 3816 4102 4253 4254 4255 3815 4102 3816 4256 4257 4253 3815 3817 3819 4258 4259 4260 3819 3818 3959 3822 3960 4104 3957 3959 3818 3820 4103 4107 3961 3958 3957 4107 3964 3824 4104 3960 3961 4261 4262 4263 3822 4104 4103 3965 686 4109 3822 4103 3820 3966 4264 555 3824 3820 4107 3969 554 4265 3964 3963 3824 4266 4267 3967 4109 3963 3965 4113 3968 4268 4109 686 545 3972 4113 4110 545 686 546 4269 4270 4271 547 546 555 3975 4114 4272 554 555 4265 4270 4273 3973 3969 4265 3967 4273 4274 4116 3967 4268 3968 4120 3977 4275 4268 4110 4113 3834 4120 4117 3972 4110 4115 4119 4276 4121 4115 4272 4114 4276 4277 4122 4272 3973 3975 4278 4279 4280 3973 4116 3974 4281 4126 4278 4275 3977 4116 4128 3982 4282 4117 4120 4275 3984 4128 4125 4117 4121 3834 4127 4283 3983 4121 4122 3979 4283 4284 4129 4122 4123 3980 4284 4285 4130 4123 4124 3981 4285 4286 4131 4282 3982 4124 4286 4287 4132 4125 4128 4282 4287 4288 4133 3983 3984 4125 4289 4290 4291 4129 3841 3983 4292 4137 4289 4130 3986 4129 4139 3992 4293 4131 3987 4130 3994 4139 4136 4131 4132 3988 4138 4294 3993 4132 4133 3989 4294 4295 4140 4133 4134 3990 4295 4296 4141 4134 4135 3991 4297 4144 4298 4293 3992 4135 4146 3998 4299 4136 4139 4293 3855 4146 4143 4136 3993 3994 4145 4300 4147 3993 4140 3850 4301 4302 4303 4140 4141 3996 3859 4148 4304 3997 4141 4142 4302 4305 4150 4142 4299 3998 4154 4002 4306 4299 4143 4146 4005 4154 4151 3855 4143 4147 4307 4308 4309 4000 4147 4149 4006 4155 4310 4148 4149 4304 4311 4312 4313 3859 4304 4150 4159 4158 4314 4002 4150 4306 4010 4159 4315 4151 4154 4306 4316 4317 4008 4156 4005 4151 4160 4009 4318 4310 4155 4156 4015 4160 4319 4310 4157 4006 4320 4321 4013 4314 4158 4157 4161 4014 4322 4315 4159 4314 4162 4161 4323 4315 4008 4010 3877 4162 4324 4008 4318 4009 4166 3877 4325 4319 4160 4318 4167 4166 4326 4319 4013 4015 4168 4167 4327 4013 4322 4014 4169 4168 4328 4322 4323 4161 4170 4169 4329 4323 4324 4162 4171 4170 4330 4324 4325 3877 4172 4171 4331 4166 4325 4326 4173 4172 4332 4167 4326 4327 4174 4173 4333 4168 4327 4328 4175 4174 4334 4169 4328 4329 4176 4175 4335 4170 4329 4330 4177 4176 4336 4171 4330 4331 4178 4177 4337 4172 4331 4332 4179 4178 4338 4173 4332 4333 4180 4179 4339 4174 4333 4334 4035 4180 4340 4175 4334 4335 4341 4342 4343 4335 4336 4176 4181 4034 4344 4336 4337 4177 4039 4181 4345 4337 4338 4178 4185 4039 4346 4339 4179 4338 4186 4185 4182 4340 4180 4339 4043 4186 4347 4340 4033 4035 4348 4349 4350 4344 4034 4033 4044 4187 4351 4345 4181 4344 4352 4353 4354 4039 4345 4346 4047 4189 4355 4182 4185 4346 4356 4357 4358 4186 4182 4347 3898 4191 4359 4188 4043 4347 4357 4360 4193 4187 4188 4351 4197 4048 4361 4044 4351 4190 4050 4197 4194 4189 4190 4355 4196 4362 4198 4047 4355 4192 4363 4364 4365 4192 4359 4191 4053 4199 4366 3898 4359 4193 4364 4367 4052 4193 4361 4048 4367 4368 4201 4361 4194 4197 4368 4369 4202 4194 4198 4050 4370 4205 4371 4198 4200 4051 4207 4057 4372 4366 4199 4200 4060 4207 4204 4366 4052 4053 4206 4373 4058 4052 4201 3905 4373 4374 4061 4201 4202 4055 4374 4375 4208 4202 4203 4056 4375 4376 4209 4372 4057 4203 4376 4377 4210 4204 4207 4372 4377 4378 4211 4058 4060 4204 4378 4379 4212 4061 4059 4058 4380 4215 4381 4208 3913 4061 4217 4068 4382 4209 4063 4208 4070 4217 4214 4209 4210 4064 4216 4383 4069 4210 4211 4065 4383 4384 4218 4211 4212 4066 4384 4385 4219 4212 4213 4067 4385 4386 4220 4382 4068 4213 4224 4074 4387 4214 4217 4382 4077 4224 4221 4214 4069 4070 4223 4388 4075 4069 4218 3921 4388 4389 4225 4218 4219 4072 4229 4079 4390 4219 4220 4073 4081 4229 4226 4220 4387 4074 4228 4391 4230 4387 4221 4224 3930 4085 139 4077 4221 4075 140 4392 141 4076 4075 4225 4083 4231 4393 4079 4225 4390 4394 4395 4082 4229 4390 4226 4232 148 4396 4081 4226 4230 4084 113 156 114 4084 4397 4232 149 148 3930 139 141 4398 4236 4397 4231 141 4393 4399 4237 4398 4083 4393 4082 4400 4238 4399 148 4082 4396 4397 4084 150 156 113 4232 4093 4234 4092 4233 4091 4092 4238 3940 4088 114 4397 4236 4091 4401 4241 4236 4398 4237 4241 4402 4242 4238 4237 4399 4403 4233 4235 4093 4400 4234 4243 4240 4404 4404 4405 4097 4241 4242 4094 4401 4091 4233 4240 4406 4404 4402 4241 4401 4407 4244 4098 4242 4239 4096 4408 4409 4407 4410 4245 4411 3945 4097 3946 4243 4404 4097 4407 4098 4405 4245 3529 3528 4099 4098 4244 4244 4411 4245 3531 4245 3528 3527 3813 4101 3951 3812 3814 3950 3812 3951 4101 4249 4102 3812 4412 4249 4413 4254 3817 4413 3816 4412 4254 4257 3818 3816 4413 3817 4260 3961 3957 3817 4254 3818 4104 3961 4259 3818 4257 3957 4414 4415 4416 4257 4260 3957 4417 4414 4418 4259 3961 4260 3964 4106 4262 4104 4259 4105 4262 687 3965 4108 4103 4105 684 4419 549 4108 4107 4103 4420 4421 4264 4106 3964 4107 4264 4266 4265 4262 3965 3964 4422 4423 4267 3965 687 686 4267 4111 4268 683 546 686 4424 4425 4112 555 546 3966 4112 4426 4115 4265 555 4264 4426 4270 4272 3967 4265 4266 4269 4427 4273 4268 3967 4267 4428 4429 4430 4268 4111 4110 4274 4118 4275 4115 4110 4112 4429 4431 4119 4272 4115 4426 4431 4432 4276 4272 4270 3973 4433 4280 4434 3973 4273 4116 4277 4435 4123 4116 4274 4275 4435 4279 4124 4118 4117 4275 4279 4126 4282 4117 4119 4121 4281 4436 4127 4121 4276 4122 4436 4437 4283 4122 4277 4123 4437 4438 4284 4123 4435 4124 4438 4439 4285 4124 4279 4282 4439 4440 4286 4126 4125 4282 4441 4442 4443 4127 3983 4125 4444 4291 4441 4283 4129 3983 4288 4445 4134 4284 4130 4129 4445 4290 4135 4285 4131 4130 4290 4137 4293 4131 4286 4132 4292 4446 4138 4132 4287 4133 4446 4447 4294 4133 4288 4134 4447 4448 4295 4134 4445 4135 4449 4298 4450 4135 4290 4293 4296 4451 4142 4137 4136 4293 4451 4144 4299 4136 4138 3993 4297 4452 4145 3993 4294 4140 4452 4453 4300 4140 4295 4141 4300 4454 4149 4141 4296 4142 4454 4302 4304 4299 4142 4451 4301 4455 4305 4299 4144 4143 4305 4152 4306 4147 4143 4145 4456 4457 4153 4149 4147 4300 4153 4458 4156 4304 4149 4454 4458 4308 4310 4150 4304 4302 4308 4459 4157 4306 4150 4305 4459 4312 4314 4151 4306 4152 4312 4316 4315 4153 4156 4151 4460 4461 4462 4458 4310 4156 4317 4463 4318 4308 4157 4310 4463 4320 4319 4157 4459 4314 4464 4465 4466 4312 4315 4314 4321 4467 4322 4316 4008 4315 4467 4468 4323 4008 4317 4318 4468 4469 4324 4318 4463 4319 4469 4470 4325 4319 4320 4013 4470 4471 4326 4013 4321 4322 4471 4472 4327 4322 4467 4323 4472 4473 4328 4323 4468 4324 4473 4474 4329 4324 4469 4325 4474 4475 4330 4325 4470 4326 4475 4476 4331 4327 4326 4471 4476 4477 4332 4328 4327 4472 4477 4478 4333 4329 4328 4473 4478 4479 4334 4330 4329 4474 4479 4480 4335 4331 4330 4475 4480 4481 4336 4332 4331 4476 4481 4482 4337 4333 4332 4477 4482 4483 4338 4334 4333 4478 4483 4484 4339 4335 4334 4479 4484 4485 4340 4336 4335 4480 4485 4486 4033 4336 4481 4337 4486 4342 4344 4337 4482 4338 4342 4487 4345 4338 4483 4339 4487 4183 4346 4339 4484 4340 4488 4489 4184 4485 4033 4340 4184 4490 4347 4033 4486 4344 4490 4491 4188 4342 4345 4344 4491 4349 4351 4487 4346 4345 4349 4492 4190 4182 4346 4183 4492 4353 4355 4184 4347 4182 4353 4493 4192 4188 4347 4490 4493 4357 4359 4491 4351 4188 4356 4494 4360 4190 4351 4349 4360 4195 4361 4492 4355 4190 4495 4496 4196 4192 4355 4353 4496 4497 4362 4359 4192 4493 4362 4498 4200 4359 4357 4193 4498 4364 4366 4361 4193 4360 4363 4499 4367 4361 4195 4194 4499 4500 4368 4194 4196 4198 4501 4371 4502 4198 4362 4200 4369 4503 4203 4200 4498 4366 4503 4205 4372 4366 4364 4052 4370 4504 4206 4052 4367 4201 4504 4505 4373 4201 4368 4202 4505 4506 4374 4202 4369 4203 4506 4507 4375 4203 4503 4372 4507 4508 4376 4205 4204 4372 4508 4509 4377 4206 4058 4204 4510 4511 4512 4373 4061 4058 4513 4381 4510 4374 4208 4061 4379 4514 4213 4375 4209 4208 4514 4215 4382 4209 4376 4210 4380 4515 4216 4210 4377 4211 4515 4516 4383 4211 4378 4212 4516 4517 4384 4212 4379 4213 4517 4518 4385 4213 4514 4382 4519 4520 4521 4215 4214 4382 4386 4222 4387 4214 4216 4069 4520 4522 4223 4069 4383 4218 4522 4523 4388 4218 4384 4219 4524 4525 4526 4219 4385 4220 4389 4227 4390 4387 4220 4386 4525 4527 4228 4221 4387 4222 4528 4529 4530 4221 4223 4075 4391 140 139 4225 4075 4388 4529 4531 4392 4390 4225 4389 4392 4394 4393 4226 4390 4227 4532 4533 4395 4230 4226 4228 4395 157 4396 4391 139 4230 4534 4535 153 4397 150 144 156 4232 4396 4393 141 4392 4398 144 4536 4082 4393 4394 4537 4399 4536 4396 4082 4395 4538 4400 4537 156 4396 157 142 144 150 155 4084 156 4539 4540 4541 4403 4401 4233 4400 4093 4238 144 4398 4397 4542 4402 4401 4398 4536 4399 4402 4540 4239 4399 4537 4400 4543 4403 4544 4235 4234 4538 4406 4240 4539 4545 4404 4406 4402 4239 4242 4542 4401 4403 4408 4405 4545 4542 4540 4402 4545 4406 4546 4239 4539 4240 4407 4409 4411 4409 4547 4548 4097 4405 4098 4405 4404 4545 3814 4410 4549 4410 3529 4245 4244 4407 4411 4410 4411 4550 3814 3529 4410 3812 4249 3813 4551 3950 3949 4551 4251 3950 4249 4412 3816 3950 4552 4412 4553 4247 4554 4255 4413 4552 4555 4556 4557 4254 4413 4255 4557 4558 4559 4254 4253 4257 4105 4259 4415 4257 4256 4260 4108 4105 4414 4258 4260 4256 4106 4417 4263 4415 4259 4258 4560 4561 4562 4414 4105 4415 4261 684 687 4414 4417 4108 4420 3966 681 4108 4417 4106 4563 4564 4565 4263 4262 4106 4422 4266 4421 687 4262 4261 4566 4567 4568 687 684 683 4424 4111 4423 681 3966 683 4569 4425 4566 4264 3966 4420 4271 4426 4425 4421 4266 4264 4570 4571 4269 4267 4266 4422 4572 4427 4571 4111 4267 4423 4573 4274 4427 4111 4424 4112 4429 4118 4573 4426 4112 4425 4574 4431 4428 4270 4426 4271 4575 4432 4574 4270 4269 4273 4576 4277 4432 4273 4427 4274 4280 4435 4576 4118 4274 4573 4433 4577 4278 4118 4429 4119 4577 4578 4281 4119 4431 4276 4579 4436 4578 4276 4432 4277 4580 4437 4579 4277 4576 4435 4581 4438 4580 4435 4280 4279 4582 4583 4584 4279 4278 4126 4443 4584 4585 4281 4127 4126 4586 4287 4440 4436 4283 4127 4442 4288 4586 4437 4284 4283 4291 4445 4442 4284 4438 4285 4444 4587 4289 4285 4439 4286 4587 4588 4292 4286 4440 4287 4589 4446 4588 4287 4586 4288 4590 4447 4589 4288 4442 4445 4450 4591 4592 4445 4291 4290 4593 4296 4448 4290 4289 4137 4298 4451 4593 4137 4292 4138 4449 4594 4297 4138 4446 4294 4595 4452 4594 4294 4447 4295 4596 4597 4598 4295 4448 4296 4303 4454 4453 4451 4296 4593 4596 4599 4301 4144 4451 4298 4600 4601 4602 4144 4297 4145 4456 4152 4455 4300 4145 4452 4603 4457 4600 4454 4300 4453 4309 4458 4457 4303 4302 4454 4604 4605 4307 4305 4302 4301 4313 4459 4307 4455 4152 4305 4606 4607 4311 4153 4152 4456 4608 4316 4311 4457 4458 4153 4609 4317 4608 4309 4308 4458 4461 4463 4609 4307 4459 4308 4610 4320 4461 4459 4313 4312 4611 4321 4610 4311 4316 4312 4465 4467 4611 4608 4317 4316 4612 4468 4465 4317 4609 4463 4613 4469 4612 4463 4461 4320 4614 4470 4613 4320 4610 4321 4615 4471 4614 4467 4321 4611 4615 4616 4472 4467 4465 4468 4617 4473 4616 4468 4612 4469 4163 4474 4617 4469 4613 4470 4618 4475 4163 4470 4614 4471 4619 4476 4618 4472 4471 4615 4620 4477 4619 4473 4472 4616 4479 4621 4622 4474 4473 4617 4623 4624 4625 4475 4474 4163 4626 4480 4622 4476 4475 4618 4627 4481 4626 4477 4476 4619 4628 4482 4627 4478 4477 4620 4629 4483 4628 4479 4478 4621 4630 4484 4629 4480 4479 4622 4631 4485 4630 4481 4480 4626 4343 4486 4631 4482 4481 4627 4632 4633 4341 4482 4628 4483 4634 4487 4341 4483 4629 4484 4488 4183 4634 4484 4630 4485 4635 4636 4637 4631 4486 4485 4638 4490 4489 4486 4343 4342 4350 4491 4638 4342 4341 4487 4639 4640 4348 4634 4183 4487 4354 4492 4348 4488 4184 4183 4641 4642 4352 4489 4490 4184 4358 4493 4352 4638 4491 4490 4643 4644 4356 4350 4349 4491 4645 4646 4647 4492 4349 4348 4495 4195 4494 4354 4353 4492 4648 4496 4645 4493 4353 4352 4649 4650 4651 4357 4493 4358 4365 4498 4497 4360 4357 4356 4649 4652 4363 4195 4360 4494 4653 4499 4652 4195 4495 4196 4502 4654 4655 4196 4496 4362 4656 4369 4500 4362 4497 4498 4371 4503 4656 4364 4498 4365 4501 4657 4370 4364 4363 4367 4658 4504 4657 4367 4499 4368 4659 4505 4658 4368 4500 4369 4660 4506 4659 4369 4656 4503 4661 4507 4660 4503 4371 4205 4662 4663 4664 4370 4206 4205 4512 4664 4665 4504 4373 4206 4666 4378 4509 4505 4374 4373 4511 4379 4666 4506 4375 4374 4381 4514 4511 4375 4507 4376 4513 4667 4380 4376 4508 4377 4668 4515 4667 4377 4509 4378 4669 4516 4668 4378 4666 4379 4670 4517 4669 4379 4511 4514 4521 4671 4672 4514 4381 4215 4673 4386 4518 4380 4216 4215 4520 4222 4673 4216 4515 4383 4519 4674 4522 4383 4516 4384 4675 4523 4674 4384 4517 4385 4676 4389 4523 4385 4518 4386 4525 4227 4676 4222 4386 4673 4677 4527 4524 4223 4222 4520 4678 4391 4527 4223 4522 4388 4529 140 4678 4389 4388 4523 4679 4680 4681 4227 4389 4676 4532 4394 4531 4228 4227 4525 4682 4683 4684 4391 4228 4527 4685 157 4533 4678 140 4391 151 155 4685 140 4529 4392 4686 4687 4688 4394 4392 4531 4536 143 4689 4394 4532 4395 4537 4689 4690 157 4395 4533 4686 4538 4690 155 157 4685 152 143 142 151 150 155 4235 4544 4403 4403 4543 4542 4538 4234 4400 144 143 4536 4542 4691 4540 4689 4537 4536 4692 4693 4543 4537 4690 4538 4406 4694 4546 4235 4686 4544 4695 4696 4697 4545 4546 4698 4540 4539 4239 4691 4542 4543 4547 4408 4698 4541 4540 4691 4548 4550 4409 4539 4694 4406 4548 4699 4700 3949 3951 4701 4405 4408 4407 4408 4545 4698 3951 4549 4701 4410 4550 4549 4411 4409 4550 4550 4702 4549 3814 4549 3951 3812 3950 4412 4252 4251 4551 4703 4704 4705 4412 4552 4413 4706 4552 4251 4707 4708 4253 4707 4255 4706 4708 4709 4256 4255 4707 4253 4415 4258 4710 4256 4253 4708 4711 4712 4713 4256 4709 4258 4714 4715 4716 4710 4258 4709 4263 4717 4718 4416 4415 4710 4718 4419 4261 4418 4414 4416 695 692 696 4417 4418 4717 4719 4420 682 4717 4263 4417 4720 4421 4719 4261 4263 4718 4563 4422 4720 684 4261 4419 4721 4423 4563 549 681 684 4566 4424 4721 682 4420 681 4722 4723 4724 4421 4420 4719 4570 4271 4569 4720 4422 4421 4722 4725 4571 4423 4422 4563 4726 4727 4728 4424 4423 4721 4430 4573 4572 4425 4424 4566 4726 4729 4428 4271 4425 4569 4730 4574 4729 4269 4271 4570 4731 4732 4733 4269 4571 4427 4434 4576 4575 4573 4427 4572 4731 4734 4433 4429 4573 4430 4734 4735 4577 4429 4428 4431 4735 4736 4578 4431 4574 4432 4737 4579 4736 4432 4575 4576 4738 4739 4740 4576 4434 4280 4583 4740 4741 4280 4433 4278 4742 4439 4581 4278 4577 4281 4582 4440 4742 4578 4436 4281 4443 4586 4582 4436 4579 4437 4585 4743 4441 4437 4580 4438 4743 4744 4444 4438 4581 4439 4744 4745 4587 4439 4742 4440 4745 4746 4588 4440 4582 4586 4747 4589 4746 4586 4443 4442 4591 4748 4749 4442 4441 4291 4750 4448 4590 4291 4444 4289 4450 4593 4750 4292 4289 4587 4592 4751 4449 4292 4588 4446 4751 4752 4594 4446 4589 4447 4753 4595 4752 4447 4590 4448 4754 4453 4595 4448 4750 4593 4596 4303 4754 4298 4593 4450 4598 4755 4599 4297 4298 4449 4756 4455 4599 4297 4594 4452 4600 4456 4756 4453 4452 4595 4757 4758 4759 4303 4453 4754 4604 4309 4603 4596 4301 4303 4757 4760 4605 4455 4301 4599 4606 4313 4605 4756 4456 4455 4761 4762 4763 4457 4456 4600 4764 4608 4607 4603 4309 4457 4462 4609 4764 4309 4604 4307 4765 4766 4460 4605 4313 4307 4767 4610 4460 4313 4606 4311 4466 4611 4767 4311 4607 4608 4768 4769 4770 4764 4609 4608 4771 4612 4464 4609 4462 4461 4772 4613 4771 4461 4460 4610 4773 4614 4772 4610 4767 4611 4774 4615 4773 4465 4611 4466 4774 4775 4616 4612 4465 4464 4775 4164 4617 4612 4771 4613 4618 4165 4776 4613 4772 4614 4619 4776 4777 4614 4773 4615 4620 4777 4778 4616 4615 4774 4621 4778 4779 4617 4616 4775 4621 4478 4620 4164 4163 4617 4779 4780 4622 4165 4618 4163 4780 4781 4626 4619 4618 4776 4782 4627 4781 4620 4619 4777 4624 4628 4782 4621 4620 4778 4783 4629 4624 4622 4621 4779 4784 4630 4783 4626 4622 4780 4785 4631 4784 4627 4626 4781 4632 4343 4785 4628 4627 4782 4786 4787 4788 4628 4624 4629 4789 4634 4633 4629 4783 4630 4790 4488 4789 4630 4784 4631 4791 4489 4790 4785 4343 4631 4635 4638 4791 4343 4632 4341 4639 4350 4635 4341 4633 4634 4792 4793 4640 4789 4488 4634 4641 4354 4640 4790 4489 4488 4794 4795 4642 4791 4638 4489 4643 4358 4642 4635 4350 4638 4796 4797 4644 4639 4348 4350 4798 4494 4644 4354 4348 4640 4645 4495 4798 4641 4352 4354 4799 4648 4647 4358 4352 4642 4800 4497 4648 4356 4358 4643 4649 4365 4800 4494 4356 4644 4651 4801 4652 4495 4494 4798 4654 4802 4803 4495 4645 4496 4804 4500 4653 4496 4648 4497 4502 4656 4804 4365 4497 4800 4655 4805 4501 4363 4365 4649 4805 4806 4657 4363 4652 4499 4807 4658 4806 4499 4653 4500 4808 4659 4807 4500 4804 4656 4809 4810 4811 4656 4502 4371 4663 4811 4812 4371 4501 4370 4813 4508 4661 4657 4504 4370 4662 4509 4813 4658 4505 4504 4512 4666 4662 4505 4659 4506 4665 4814 4510 4506 4660 4507 4814 4815 4513 4507 4661 4508 4815 4816 4667 4508 4813 4509 4817 4668 4816 4509 4662 4666 4818 4669 4817 4666 4512 4511 4671 4819 4820 4511 4510 4381 4821 4518 4670 4381 4513 4380 4521 4673 4821 4515 4380 4667 4672 4822 4519 4515 4668 4516 4822 4823 4674 4516 4669 4517 4824 4825 4826 4517 4670 4518 4526 4676 4675 4673 4518 4821 4824 4827 4524 4520 4673 4521 4828 4829 4830 4522 4520 4519 4530 4678 4677 4523 4522 4674 4828 4831 4528 4676 4523 4675 4832 4531 4528 4525 4676 4526 4679 4532 4832 4527 4525 4524 4833 4533 4679 4678 4527 4677 4682 4685 4833 4530 4529 4678 154 151 4682 4528 4531 4529 4834 4534 152 4832 4532 4531 4835 4689 153 4533 4532 4679 4687 4690 4835 4685 4533 4833 152 4534 153 151 4685 4682 4836 4837 4838 142 151 154 4544 4692 4543 4693 4691 4543 4686 4235 4538 143 153 4689 4691 4837 4541 4689 4835 4690 4541 4836 4694 4690 4687 4686 4839 4693 4840 4692 4544 4688 4695 4546 4841 4697 4698 4695 4541 4694 4539 4693 4837 4691 4699 4547 4697 4836 4541 4837 4700 4702 4548 4841 4546 4694 4546 4695 4698 4700 4842 4843 4408 4547 4409 4547 4698 4697 4701 4844 4845 4701 4551 3949 4550 4548 4702 4701 4702 4844 4549 4702 4701 3950 4251 4552 4248 4250 4252 4247 4250 4248 4552 4706 4255 4250 4846 4706 4708 4847 4555 4847 4707 4846 4555 4559 4709 4708 4707 4847 4713 4416 4710 4708 4555 4709 4418 4416 4712 4559 4710 4709 4717 4418 4848 4559 4713 4710 4718 4849 4561 4712 4416 4713 4561 550 4419 4848 4418 4712 548 4850 682 4717 4848 4849 690 4719 4850 4849 4718 4717 4564 4720 690 4419 4718 4561 4851 4852 4565 549 4419 550 4567 4721 4565 549 548 682 4853 4854 4568 4850 4719 682 4855 4569 4568 4720 4719 690 4722 4570 4855 4564 4563 4720 4724 4856 4725 4721 4563 4565 4857 4572 4725 4566 4721 4567 4726 4430 4857 4569 4566 4568 4728 4858 4729 4570 4569 4855 4732 4859 4860 4571 4570 4722 4861 4575 4730 4571 4725 4572 4731 4434 4861 4430 4572 4857 4733 4862 4734 4428 4430 4726 4862 4863 4735 4428 4729 4574 4863 4864 4736 4574 4730 4575 4739 4865 4866 4575 4861 4434 4867 4580 4737 4434 4731 4433 4738 4581 4867 4433 4734 4577 4583 4742 4738 4578 4577 4735 4741 4868 4584 4578 4736 4579 4868 4869 4585 4579 4737 4580 4869 4870 4743 4580 4867 4581 4870 4871 4744 4581 4738 4742 4871 4872 4745 4742 4583 4582 4872 4873 4746 4582 4584 4443 4748 4874 4875 4443 4585 4441 4876 4590 4747 4441 4743 4444 4591 4750 4876 4587 4444 4744 4749 4877 4592 4588 4587 4745 4877 4878 4751 4588 4746 4589 4878 4879 4752 4589 4747 4590 4880 4881 4882 4590 4876 4750 4597 4754 4753 4450 4750 4591 4880 4883 4598 4449 4450 4592 4884 4885 4886 4594 4449 4751 4601 4756 4755 4595 4594 4752 4885 4887 4602 4754 4595 4753 4888 4603 4602 4596 4754 4597 4757 4604 4888 4598 4599 4596 4889 4890 4891 4756 4599 4755 4892 4606 4760 4601 4600 4756 4892 4893 4607 4603 4600 4602 4762 4764 4893 4888 4604 4603 4765 4462 4762 4604 4757 4605 4894 4895 4896 4760 4606 4605 4897 4767 4766 4606 4892 4607 4898 4466 4897 4607 4893 4764 4898 4899 4464 4762 4462 4764 4769 4771 4899 4462 4765 4460 4900 4772 4769 4460 4766 4767 4901 4773 4900 4767 4897 4466 4902 4774 4901 4464 4466 4898 4902 4903 4775 4771 4464 4899 4903 4904 4164 4772 4771 4769 4904 4905 4165 4773 4772 4900 4905 4906 4776 4774 4773 4901 4906 4907 4777 4902 4775 4774 4907 4908 4778 4903 4164 4775 4908 4909 4779 4904 4165 4164 4909 4910 4780 4905 4776 4165 4910 4911 4781 4906 4777 4776 4911 4625 4782 4778 4777 4907 4912 4913 4914 4779 4778 4908 4912 4783 4623 4780 4779 4909 4915 4784 4912 4781 4780 4910 4916 4785 4915 4782 4781 4911 4917 4632 4916 4624 4782 4625 4917 4918 4633 4624 4623 4783 4787 4789 4918 4783 4912 4784 4919 4790 4787 4784 4915 4785 4636 4791 4919 4785 4916 4632 4920 4921 4637 4632 4917 4633 4792 4639 4637 4633 4918 4789 4922 4923 4924 4787 4790 4789 4794 4641 4793 4919 4791 4790 4925 4926 4927 4636 4635 4791 4796 4643 4795 4637 4639 4635 4928 4929 4930 4792 4640 4639 4646 4798 4797 4793 4641 4640 4929 4931 4647 4794 4642 4641 4932 4933 4934 4643 4642 4795 4650 4800 4799 4796 4644 4643 4932 4935 4651 4798 4644 4797 4935 4936 4801 4645 4798 4646 4937 4653 4801 4645 4647 4648 4654 4804 4937 4800 4648 4799 4803 4938 4655 4649 4800 4650 4938 4939 4805 4652 4649 4651 4939 4940 4806 4652 4801 4653 4941 4942 4943 4653 4937 4804 4810 4943 4944 4804 4654 4502 4945 4660 4808 4502 4655 4501 4809 4661 4945 4501 4805 4657 4663 4813 4809 4658 4657 4806 4812 4946 4664 4658 4807 4659 4946 4947 4665 4659 4808 4660 4947 4948 4814 4660 4945 4661 4948 4949 4815 4661 4809 4813 4949 4950 4816 4813 4663 4662 4950 4951 4817 4662 4664 4512 4819 4952 4953 4512 4665 4510 4954 4670 4818 4510 4814 4513 4671 4821 4954 4667 4513 4815 4820 4955 4672 4668 4667 4816 4955 4956 4822 4668 4817 4669 4957 4825 4958 4669 4818 4670 4959 4675 4823 4670 4954 4821 4824 4526 4959 4521 4821 4671 4826 4960 4827 4519 4521 4672 4961 4677 4827 4674 4519 4822 4828 4530 4961 4675 4674 4823 4830 4962 4831 4526 4675 4959 4680 4832 4831 4824 4524 4526 4963 4964 4681 4677 4524 4827 4683 4833 4681 4961 4530 4677 4965 4966 4684 4828 4528 4530 4834 154 4684 4831 4832 4528 161 147 4967 4679 4832 4680 146 4835 4535 4833 4679 4681 4968 4687 146 4683 4682 4833 4969 4688 4968 4684 154 4682 4535 4534 4970 154 4834 152 4692 4840 4693 4693 4839 4837 4688 4544 4686 153 4535 4835 4971 4972 4696 4835 146 4687 4836 4973 4841 4687 4968 4688 4839 4974 4975 4692 4969 4840 4696 4695 4976 4697 4696 4977 4836 4841 4694 4838 4837 4839 4842 4699 4977 4838 4973 4836 4977 4696 4972 4841 4976 4695 4700 4843 4844 4843 4978 4979 4547 4699 4548 4699 4697 4977 4252 4845 4980 4845 4551 4701 4702 4700 4844 4845 4844 4981 4252 4551 4845 4250 4706 4251 4554 4247 4246 4982 4983 4984 4706 4846 4707 4247 4985 4846 4983 4986 4987 4985 4556 4847 4988 4989 4990 4555 4847 4556 4991 4992 4988 4555 4557 4559 4716 4848 4712 4559 4558 4713 4849 4848 4715 4558 4711 4713 4993 4994 4995 4711 4716 4712 550 4560 691 4848 4716 4715 692 688 4850 4849 4715 4562 4996 4997 689 4562 4561 4849 4851 4564 689 4561 4560 550 4998 4999 5000 691 548 550 4853 4567 4852 548 692 4850 4999 5001 4854 688 690 4850 4723 4855 4854 689 4564 690 5002 5003 4724 4851 4565 4564 5004 5005 5006 4567 4565 4852 4727 4857 4856 4853 4568 4567 5005 5007 4728 4855 4568 4854 5008 5009 4859 4722 4855 4723 5010 4730 4858 4725 4722 4724 4732 4861 5010 4857 4725 4856 4860 5011 4733 4726 4857 4727 5011 5012 4862 4729 4726 4728 5012 5013 4863 4730 4729 4858 5014 4865 5015 4730 5010 4861 5016 4737 4864 4861 4732 4731 4739 4867 5016 4734 4731 4733 4866 5017 4740 4735 4734 4862 5017 5018 4741 4736 4735 4863 5018 5019 4868 4736 4864 4737 5019 5020 4869 4737 5016 4867 5020 5021 4870 4867 4739 4738 5021 5022 4871 4738 4740 4583 5022 5023 4872 4583 4741 4584 5024 5025 4874 4584 4868 4585 5026 4747 4873 4585 4869 4743 4748 4876 5026 4744 4743 4870 4875 5027 4749 4745 4744 4871 5027 5028 4877 4746 4745 4872 5028 5029 4878 4746 4873 4747 5030 4881 5031 4747 5026 4876 5032 4753 4879 4876 4748 4591 4880 4597 5032 4592 4591 4749 4882 5033 4883 4751 4592 4877 4883 5034 4755 4752 4751 4878 4885 4601 5034 4753 4752 4879 4884 5035 4887 4597 4753 5032 4758 4888 4887 4880 4598 4597 5036 5037 4759 4883 4755 4598 4759 5038 4760 4601 4755 5034 4890 4892 5038 4885 4602 4601 4890 4763 4893 4602 4887 4888 5039 5040 4761 4758 4757 4888 5041 4765 4761 4757 4759 4760 5041 5042 4766 5038 4892 4760 4895 4897 5042 4892 4890 4893 5043 4898 4895 4893 4763 4762 5043 4770 4899 4762 4761 4765 5044 5045 5046 4765 5041 4766 5047 4900 4768 4766 5042 4897 5048 4901 5047 4897 4895 4898 5049 4902 5048 4899 4898 5043 5049 5050 4903 4769 4899 4770 5050 5051 4904 4900 4769 4768 5051 5052 4905 4901 4900 5047 5052 5053 4906 4902 4901 5048 5053 5054 4907 5049 4903 4902 5054 5055 4908 5050 4904 4903 5055 5056 4909 5051 4905 4904 5056 5057 4910 5052 4906 4905 5057 5058 4911 5053 4907 4906 5058 5059 4625 5054 4908 4907 5059 4913 4623 5055 4909 4908 5060 5061 5062 4910 4909 5056 5063 4915 4914 4911 4910 5057 5064 4916 5063 4625 4911 5058 5065 4917 5064 4623 4625 5059 5065 4788 4918 4912 4623 4913 5066 5067 5068 4912 4914 4915 5069 4919 4786 4915 5063 4916 4920 4636 5069 4916 5064 4917 5070 5071 5072 4917 5065 4918 5073 4792 4921 4918 4788 4787 5073 5074 4793 4786 4919 4787 4923 4794 5074 4919 5069 4636 4923 5075 4795 4920 4637 4636 4926 4796 5075 4921 4792 4637 4926 5076 4797 5073 4793 4792 4929 4646 5076 5074 4794 4793 4928 5077 4931 4923 4795 4794 5078 4799 4931 4796 4795 5075 4932 4650 5078 4926 4797 4796 4934 5079 4935 4646 4797 5076 5080 5081 5082 4647 4646 4929 4802 4937 4936 4931 4799 4647 5081 5083 4803 4650 4799 5078 5083 5084 4938 4651 4650 4932 5084 5085 4939 4801 4651 4935 5086 5087 4942 4801 4936 4937 4940 5088 4807 4937 4802 4654 4941 4808 5088 4654 4803 4655 4810 4945 4941 4805 4655 4938 4944 5089 4811 4806 4805 4939 5089 5090 4812 4807 4806 4940 5090 5091 4946 4807 5088 4808 5091 5092 4947 4808 4941 4945 5092 5093 4948 4945 4810 4809 5093 5094 4949 4809 4811 4663 5095 5096 5097 4663 4812 4664 5098 4952 5096 4664 4946 4665 5099 4818 4951 4665 4947 4814 4819 4954 5099 4815 4814 4948 4953 5100 4820 4816 4815 4949 5100 5101 4955 4817 4816 4950 5101 5102 4956 4817 4951 4818 4956 5103 4823 4818 5099 4954 4825 4959 5103 4671 4954 4819 4957 5104 4826 4672 4671 4820 5105 5106 5107 4822 4672 4955 4829 4961 4960 4956 4823 4822 5106 5108 4830 4959 4823 5103 5109 5110 5111 4824 4959 4825 4963 4680 4962 4826 4827 4824 5112 5113 5114 4961 4827 4960 4965 4683 4964 4829 4828 4961 5115 5116 5117 4830 4831 4828 5118 4834 4966 4962 4680 4831 5118 4970 4534 4963 4681 4680 4970 147 4535 4683 4681 4964 158 4968 145 4684 4683 4965 5119 4969 158 4834 4684 4966 4970 4967 147 5118 4534 4834 4840 4974 4839 4975 4838 4839 4969 4692 4688 4535 147 146 4838 5120 4973 4968 146 145 4973 5121 4976 4969 4968 158 5122 4975 5123 4840 5119 4974 4977 4972 5124 5124 4978 4842 4973 4976 4841 5120 4838 4975 4972 5125 5124 5121 4973 5120 4979 4981 4843 4976 4971 4696 5126 5127 4979 5128 4980 5129 4699 4842 4700 4977 5124 4842 4248 4980 5128 4845 4981 4980 4844 4843 4981 4981 5129 4980 4252 4980 4248 4250 4247 4846 5130 4553 4554 4704 4553 5130 4846 4985 4847 4553 5131 4985 5132 4989 4557 5132 4556 5131 4989 4992 4558 4556 5132 4557 5133 4716 4711 4558 4557 4989 5134 5135 5136 4558 4992 4711 4562 4715 4994 4992 5133 4711 4560 4993 697 5133 4714 4716 5137 704 702 4714 4994 4715 695 4996 688 4994 4993 4562 5138 5139 5140 4993 4560 4562 5141 4851 4997 697 691 4560 5141 5142 4852 696 692 691 4999 4853 5142 692 695 688 5143 5144 5145 4996 689 688 5002 4723 5001 4997 4851 689 5144 5146 5003 5141 4852 4851 5003 5147 4856 4853 4852 5142 5005 4727 5147 4999 4854 4853 5004 5148 5007 4723 4854 5001 5007 5149 4858 4724 4723 5002 5149 4859 5010 5003 4856 4724 5009 5150 4860 4727 4856 5147 5150 5151 5011 4728 4727 5005 5151 5152 5012 4858 4728 5007 5153 5154 5015 5010 4858 5149 5013 5155 4864 5010 4859 4732 4865 5016 5155 4733 4732 4860 5014 5156 4866 4862 4733 5011 5156 5157 5017 4863 4862 5012 5157 5158 5018 4864 4863 5013 5158 5159 5019 4864 5155 5016 5159 5160 5020 5016 4865 4739 5160 5161 5021 4739 4866 4740 5162 5163 5164 4740 5017 4741 5163 5165 5024 4741 5018 4868 5023 5166 4873 4868 5019 4869 4874 5026 5166 4870 4869 5020 5025 5167 4875 4871 4870 5021 5167 5168 5027 4872 4871 5022 5168 5169 5028 4873 4872 5023 5170 5171 5031 5026 4873 5166 5029 5172 4879 5026 4874 4748 4881 5032 5172 4749 4748 4875 5030 5173 4882 4877 4749 5027 5174 5175 5176 4878 4877 5028 5033 4886 5034 5029 4879 4878 5176 5177 4884 5032 4879 5172 5178 5179 5180 4880 5032 4881 5035 5036 4758 4882 4883 4880 5180 5181 5037 5033 5034 4883 5037 4891 5038 4886 4885 5034 5182 5183 4889 4884 4887 4885 4889 5039 4763 4887 5035 4758 5184 5185 5186 5036 4759 4758 5187 5041 5040 4759 5037 5038 5187 4896 5042 5038 4891 4890 5188 5189 4894 4890 4889 4763 5190 5043 4894 4763 5039 4761 5190 5191 4770 4761 5040 5041 5191 5192 4768 5041 5187 5042 5045 5047 5192 5042 4896 4895 5193 5048 5045 4895 4894 5043 5194 5049 5193 4770 5043 5190 5194 5195 5050 4768 4770 5191 5195 5196 5051 5047 4768 5192 5196 5197 5052 5048 5047 5045 5197 5198 5053 5049 5048 5193 5198 5199 5054 5194 5050 5049 5199 5200 5055 5195 5051 5050 5200 5201 5056 5196 5052 5051 5201 5202 5057 5197 5053 5052 5202 5203 5058 5198 5054 5053 5203 5204 5059 5199 5055 5054 5204 5205 4913 5200 5056 5055 5205 5206 4914 5057 5056 5201 5207 5063 5206 5058 5057 5202 5208 5064 5207 5059 5058 5203 5209 5065 5208 4913 5059 5204 5209 5210 4788 4914 4913 5205 5210 5211 4786 4914 5206 5063 5067 5069 5211 5063 5207 5064 5067 5212 4920 5064 5208 5065 5212 5213 4921 5065 5209 4788 5071 5073 5213 4788 5210 4786 5071 4924 5074 4786 5211 5069 5214 5215 4922 5069 5067 4920 4922 4927 5075 4920 5212 4921 5216 5217 4925 5213 5073 4921 4925 4930 5076 5073 5071 5074 5218 5219 4928 4924 4923 5074 5220 5221 5222 4922 5075 4923 5077 4933 5078 4927 4926 5075 5222 5223 4934 4925 5076 4926 5224 5225 5082 4929 5076 4930 5079 5226 4936 4931 4929 4928 5081 4802 5226 5077 5078 4931 5080 5227 5083 4932 5078 4933 5227 5228 5084 4935 4932 4934 5229 5230 5086 4936 4935 5079 5085 5231 4940 4936 5226 4802 5231 4942 5088 4803 4802 5081 5087 5232 4943 4938 4803 5083 5232 5233 4944 4939 4938 5084 5233 5234 5089 4940 4939 5085 5234 5235 5090 5088 4940 5231 5235 5236 5091 5088 4942 4941 5236 5237 5092 4941 4943 4810 5238 5239 5240 4810 4944 4811 5239 5241 5095 4811 5089 4812 5094 5242 4950 4812 5090 4946 5242 5097 4951 4946 5091 4947 4952 5099 5097 4948 4947 5092 5098 5243 4953 4949 4948 5093 5243 5244 5100 4950 4949 5094 5244 5245 5101 4951 4950 5242 5246 5247 5248 4951 5097 5099 5102 4958 5103 4819 5099 4952 5248 5249 4957 4820 4819 4953 5249 5250 5104 4955 4820 5100 5104 5251 4960 4956 4955 5101 5106 4829 5251 5102 5103 4956 5105 5252 5108 4825 5103 4958 5108 5253 4962 4826 4825 4957 5110 4963 5253 5104 4960 4826 5110 5254 4964 4829 4960 5251 5113 4965 5254 5106 4830 4829 5113 5255 4966 5108 4962 4830 5116 5118 5255 5253 4963 4962 5116 4967 4970 4963 5110 4964 5256 5257 161 5254 4965 4964 5258 163 160 5113 4966 4965 165 5119 160 5255 5118 4966 161 4967 5256 5116 4970 5118 4974 5123 4975 5122 5120 4975 5119 4840 4969 145 147 161 5259 5121 5120 145 159 158 5121 5260 4971 5119 158 160 5261 5122 5262 5123 4974 165 5125 4972 5263 5264 5124 5125 5121 4971 4976 5259 5120 5122 5126 4978 5264 5259 5260 5121 5264 5125 5265 4971 5263 4972 4979 5127 5129 5127 5266 5267 4842 4978 4843 4978 5124 5264 4554 5128 5268 4246 4248 5128 4981 4979 5129 5128 5129 5269 4554 4246 5128 4247 4553 4985 4705 4704 5130 4703 4986 4704 4985 5131 4556 4704 5270 5131 5271 5272 5273 4990 5132 5270 5274 5275 5276 4989 5132 4990 5136 4714 5133 4989 4988 4992 4994 4714 5135 5133 4992 4991 5277 5278 5279 4991 5136 5133 697 5280 702 5135 4714 5136 703 5281 694 4994 5135 4995 694 5282 4996 4993 4995 5280 5282 5283 4997 697 4993 5280 5139 5141 5283 697 702 696 5139 5000 5142 696 693 695 5284 5285 4998 695 694 4996 4998 5286 5001 5282 4997 4996 5144 5002 5286 5283 5141 4997 5287 5288 5289 5139 5142 5141 5146 5006 5147 5000 4999 5142 5289 5290 5004 4998 5001 4999 5291 5292 5293 5002 5001 5286 5148 5008 5149 5144 5003 5002 5009 5293 5294 5146 5147 5003 5294 5295 5150 5005 5147 5006 5295 5296 5151 5007 5005 5004 5297 5298 5153 5149 5007 5148 5152 5299 5013 4859 5149 5008 5299 5015 5155 4860 4859 5009 5014 5154 5300 5011 4860 5150 5300 5301 5156 5012 5011 5151 5301 5302 5157 5013 5012 5152 5302 5303 5158 5155 5013 5299 5303 5304 5159 4865 5155 5015 5305 5306 5307 4865 5014 4866 5306 5308 5162 4866 5156 5017 5161 5309 5022 5017 5157 5018 5309 5164 5023 5018 5158 5019 5164 5024 5166 5020 5019 5159 5025 5165 5310 5021 5020 5160 5310 5311 5167 5022 5021 5161 5311 5312 5168 5023 5022 5309 5312 5313 5169 5166 5023 5164 5169 5314 5029 4874 5166 5024 5314 5031 5172 4875 4874 5025 5171 5315 5030 5027 4875 5167 5315 5316 5173 5028 5027 5168 5173 5317 5033 5029 5028 5169 5317 5176 4886 5314 5172 5029 5175 5318 5177 4881 5172 5031 5177 5319 5035 4882 4881 5030 5319 5180 5036 5173 5033 4882 5320 5321 5322 5317 4886 5033 5181 5182 4891 5176 4884 4886 5323 5324 5325 5177 5035 4884 5183 5326 5039 5035 5319 5036 5326 5327 5040 5180 5037 5036 5185 5187 5327 5037 5181 4891 5185 5188 4896 4891 5182 4889 5328 5329 5330 4889 5183 5039 5331 5190 5189 5039 5326 5040 5331 5332 5191 5040 5327 5187 5332 5046 5192 4896 5187 5185 5333 5334 5335 4896 5188 4894 5336 5193 5044 4894 5189 5190 5337 5194 5336 5191 5190 5331 5337 5338 5195 5192 5191 5332 5338 5339 5196 5045 5192 5046 5339 5340 5197 5193 5045 5044 5340 5341 5198 5194 5193 5336 5341 5342 5199 5337 5195 5194 5342 5343 5200 5338 5196 5195 5343 5344 5201 5339 5197 5196 5344 5345 5202 5340 5198 5197 5345 5346 5203 5341 5199 5198 5346 5347 5204 5342 5200 5199 5347 5348 5205 5343 5201 5200 5348 5349 5206 5344 5202 5201 5349 5350 5207 5203 5202 5345 5060 5208 5350 5204 5203 5346 5351 5209 5060 5205 5204 5347 5351 5352 5210 5206 5205 5348 5352 5068 5211 5207 5206 5349 5353 5354 5066 5207 5350 5208 5066 5355 5212 5208 5060 5209 5355 5072 5213 5210 5209 5351 5356 5357 5070 5210 5352 5211 5070 5214 4924 5211 5068 5067 5358 5359 5360 5067 5066 5212 5215 5216 4927 5212 5355 5213 5361 5362 5363 5072 5071 5213 5217 5218 4930 5071 5070 4924 5363 5364 5219 5214 4922 4924 5219 5365 5077 5215 4927 4922 5365 5222 4933 5216 4925 4927 5221 5366 5223 5217 4930 4925 5223 5367 5079 4928 4930 5218 5367 5082 5226 5219 5077 4928 5225 5368 5080 5365 4933 5077 5368 5369 5227 4934 4933 5222 5370 5371 5229 5079 4934 5223 5228 5372 5085 5226 5079 5367 5372 5086 5231 5081 5226 5082 5087 5230 5373 5083 5081 5080 5373 5374 5232 5084 5083 5227 5374 5375 5233 5085 5084 5228 5375 5376 5234 5231 5085 5372 5376 5377 5235 4942 5231 5086 5378 5379 5380 4942 5087 4943 5379 5381 5238 4943 5232 4944 5237 5382 5093 4944 5233 5089 5382 5240 5094 5089 5234 5090 5240 5095 5242 5091 5090 5235 5096 5241 5383 5092 5091 5236 5383 5384 5098 5093 5092 5237 5384 5385 5243 5094 5093 5382 5385 5386 5244 5242 5094 5240 5387 5388 5246 5097 5242 5095 5245 5389 5102 5097 5096 4952 5389 5248 4958 4953 4952 5098 5247 5390 5249 5100 4953 5243 5391 5392 5393 5101 5100 5244 5250 5107 5251 5245 5102 5101 5393 5394 5105 5389 4958 5102 5395 5396 5397 4957 4958 5248 5252 5111 5253 5249 5104 4957 5397 5398 5109 5250 5251 5104 5109 5114 5254 5107 5106 5251 5399 5400 5112 5105 5108 5106 5112 5117 5255 5108 5252 5253 5401 5402 5115 5111 5110 5253 5115 5256 4967 5110 5109 5254 5403 5404 164 5114 5113 5254 5258 159 5257 5255 5113 5112 5405 5257 5256 5116 5255 5117 5262 5122 5123 5115 4967 5116 5261 5259 5122 5260 5259 5406 165 4974 5119 5257 159 161 5263 5260 5407 159 5258 160 5261 5408 5409 160 163 165 5125 5410 5265 5262 5123 166 5264 5265 5411 5412 5413 5267 5260 5263 4971 5406 5259 5261 5266 5126 5411 5407 5260 5406 5267 5269 5127 5263 5410 5125 5267 5414 5412 5413 5415 5268 4978 5126 4979 5126 5264 5411 5130 5268 5415 5128 5269 5268 5129 5127 5269 5269 5413 5268 4554 5268 5130 4553 4704 5131 4987 4986 4703 5416 5417 5418 5131 5270 5132 5419 5270 4986 5420 5421 4988 5420 4990 5419 5421 5422 4991 4988 4990 5420 5423 5424 5425 4991 4988 5421 4995 5135 5426 4991 5422 5136 5280 4995 5427 5422 5134 5136 710 709 719 5135 5134 5426 5428 5429 5430 4995 5426 5427 5281 5431 5282 5280 5427 5137 5431 5140 5283 5280 5137 702 5432 5433 5138 702 704 693 5138 5284 5000 693 703 694 5434 5435 5285 694 5281 5282 5285 5145 5286 5282 5431 5283 5143 5436 5437 5140 5139 5283 5143 5438 5146 5138 5000 5139 5438 5289 5006 5284 4998 5000 5288 5439 5290 5285 5286 4998 5290 5440 5148 5145 5144 5286 5440 5293 5008 5143 5146 5144 5294 5292 5441 5438 5006 5146 5441 5442 5295 5004 5006 5289 5443 5444 5297 5148 5004 5290 5296 5445 5152 5008 5148 5440 5445 5153 5299 5293 5009 5008 5154 5298 5446 5150 5009 5294 5300 5446 5447 5151 5150 5295 5447 5448 5301 5152 5151 5296 5448 5449 5302 5299 5152 5445 5450 5451 5452 5015 5299 5153 5451 5453 5305 5014 5015 5154 5304 5454 5160 5014 5300 5156 5454 5307 5161 5156 5301 5157 5307 5162 5309 5158 5157 5302 5163 5308 5455 5159 5158 5303 5165 5455 5456 5160 5159 5304 5310 5456 5457 5161 5160 5454 5457 5458 5311 5309 5161 5307 5459 5460 5461 5164 5309 5162 5460 5462 5463 5024 5164 5163 5313 5170 5314 5165 5025 5024 5171 5463 5464 5167 5025 5310 5315 5464 5465 5168 5167 5311 5466 5467 5468 5169 5168 5312 5316 5174 5317 5313 5314 5169 5175 5468 5469 5170 5031 5314 5469 5470 5318 5171 5030 5031 5318 5178 5319 5315 5173 5030 5179 5471 5472 5316 5317 5173 5179 5473 5181 5174 5176 5317 5473 5322 5182 5175 5177 5176 5322 5474 5183 5318 5319 5177 5474 5325 5326 5319 5178 5180 5325 5186 5327 5180 5179 5181 5475 5476 5184 5181 5473 5182 5184 5477 5188 5182 5322 5183 5477 5478 5189 5183 5474 5326 5329 5331 5478 5326 5325 5327 5329 5479 5332 5327 5186 5185 5479 5480 5046 5188 5185 5184 5480 5481 5044 5188 5477 5189 5334 5336 5481 5189 5478 5331 5482 5337 5334 5332 5331 5329 5482 5483 5338 5046 5332 5479 5483 5484 5339 5044 5046 5480 5484 5485 5340 5336 5044 5481 5485 5486 5341 5334 5337 5336 5486 5487 5342 5482 5338 5337 5487 5488 5343 5483 5339 5338 5488 5489 5344 5484 5340 5339 5489 5490 5345 5485 5341 5340 5490 5491 5346 5486 5342 5341 5491 5492 5347 5487 5343 5342 5492 5493 5348 5488 5344 5343 5493 5494 5349 5489 5345 5344 5494 5061 5350 5490 5346 5345 5495 5496 5497 5347 5346 5491 5498 5351 5062 5348 5347 5492 5498 5499 5352 5349 5348 5493 5499 5353 5068 5350 5349 5494 5500 5501 5502 5350 5061 5060 5354 5503 5355 5060 5062 5351 5503 5356 5072 5352 5351 5498 5504 5505 5506 5352 5499 5068 5357 5507 5214 5068 5353 5066 5507 5508 5215 5066 5354 5355 5508 5360 5216 5355 5503 5072 5360 5509 5217 5356 5070 5072 5509 5363 5218 5070 5357 5214 5510 5511 5512 5507 5215 5214 5364 5220 5365 5215 5508 5216 5221 5512 5513 5360 5217 5216 5514 5515 5516 5509 5218 5217 5366 5224 5367 5363 5219 5218 5225 5516 5517 5364 5365 5219 5517 5518 5368 5220 5222 5365 5519 5520 5370 5223 5222 5221 5369 5521 5228 5367 5223 5366 5521 5229 5372 5224 5082 5367 5230 5371 5522 5080 5082 5225 5373 5522 5523 5227 5080 5368 5523 5524 5374 5228 5227 5369 5524 5525 5375 5372 5228 5521 5526 5527 5528 5086 5372 5229 5527 5529 5378 5087 5086 5230 5377 5530 5236 5087 5373 5232 5530 5380 5237 5232 5374 5233 5380 5238 5382 5234 5233 5375 5239 5381 5531 5235 5234 5376 5241 5531 5532 5236 5235 5377 5383 5532 5533 5237 5236 5530 5533 5534 5384 5382 5237 5380 5534 5535 5385 5240 5382 5238 5536 5537 5387 5095 5240 5239 5386 5538 5245 5096 5095 5241 5538 5246 5389 5098 5096 5383 5247 5388 5539 5243 5098 5384 5539 5540 5390 5244 5243 5385 5390 5541 5250 5245 5244 5386 5541 5393 5107 5538 5389 5245 5394 5392 5542 5246 5248 5389 5394 5543 5252 5249 5248 5247 5543 5397 5111 5390 5250 5249 5396 5544 5398 5541 5107 5250 5398 5399 5114 5107 5393 5105 5545 5546 5400 5394 5252 5105 5400 5401 5117 5252 5543 5111 5547 5548 5402 5397 5109 5111 5402 5405 5256 5109 5398 5114 5405 5549 5257 5399 5112 5114 164 5258 5549 5112 5400 5117 5550 173 5551 5117 5401 5115 5552 5549 5405 5402 5256 5115 5262 5408 5261 5261 5409 5406 166 5123 165 5257 5549 5258 5406 5553 5407 5258 164 163 5407 5554 5410 166 163 162 5555 5409 5556 5408 5262 170 5557 5265 5558 5559 5411 5557 5407 5410 5263 5409 5553 5406 5414 5266 5559 5553 5554 5407 5559 5557 5560 5558 5265 5410 5265 5557 5411 5412 5561 5562 5126 5266 5127 5266 5411 5559 5415 5563 5564 4703 4705 5415 5269 5267 5413 5413 5563 5415 5130 5415 4705 4704 4986 5270 4984 4983 4987 4982 5272 4983 5270 5419 4990 4983 5565 5419 5421 5566 5274 5566 5420 5565 5274 5567 5422 5421 5420 5566 5426 5134 5568 5422 5421 5274 5279 5427 5426 5422 5567 5134 5137 5427 5278 5568 5134 5567 707 5569 703 5279 5426 5568 5569 5570 5281 5279 5278 5427 5570 5430 5431 5278 706 5137 5430 5432 5140 704 5137 706 5571 5572 5573 704 707 703 5433 5434 5284 703 5569 5281 5574 5575 5576 5281 5570 5431 5435 5436 5145 5431 5430 5140 5437 5574 5577 5432 5138 5140 5437 5287 5438 5138 5433 5284 5288 5578 5579 5434 5285 5284 5580 5581 5582 5435 5145 5285 5439 5291 5440 5145 5436 5143 5292 5580 5583 5437 5438 5143 5441 5583 5584 5287 5289 5438 5443 5585 5586 5290 5289 5288 5442 5587 5296 5440 5290 5439 5587 5297 5445 5291 5293 5440 5298 5444 5588 5292 5294 5293 5446 5588 5589 5295 5294 5441 5447 5589 5590 5296 5295 5442 5591 5592 5593 5445 5296 5587 5450 5591 5594 5153 5445 5297 5449 5595 5303 5154 5153 5298 5595 5452 5304 5300 5154 5446 5452 5305 5454 5301 5300 5447 5306 5453 5596 5302 5301 5448 5308 5596 5597 5303 5302 5449 5455 5597 5598 5304 5303 5595 5456 5598 5599 5454 5304 5452 5457 5599 5600 5307 5454 5305 5459 5601 5602 5162 5307 5306 5458 5603 5312 5163 5162 5308 5603 5461 5313 5165 5163 5455 5461 5463 5170 5456 5310 5165 5464 5462 5604 5311 5310 5457 5465 5604 5605 5312 5311 5458 5465 5606 5316 5313 5312 5603 5606 5468 5174 5461 5170 5313 5469 5467 5607 5463 5171 5170 5608 5609 5610 5464 5315 5171 5470 5471 5178 5465 5316 5315 5472 5608 5611 5606 5174 5316 5472 5320 5473 5174 5468 5175 5321 5612 5613 5469 5318 5175 5321 5323 5474 5318 5470 5178 5324 5614 5615 5178 5471 5179 5324 5475 5186 5179 5472 5473 5616 5617 5476 5473 5320 5322 5476 5618 5477 5322 5321 5474 5618 5330 5478 5325 5474 5323 5619 5620 5328 5325 5324 5186 5328 5621 5479 5186 5475 5184 5621 5622 5480 5477 5184 5476 5622 5335 5481 5478 5477 5618 5623 5624 5625 5478 5330 5329 5333 5626 5482 5479 5329 5328 5626 5627 5483 5480 5479 5621 5627 5628 5484 5481 5480 5622 5628 5629 5485 5334 5481 5335 5629 5630 5486 5333 5482 5334 5630 5631 5487 5626 5483 5482 5631 5632 5488 5627 5484 5483 5632 5633 5489 5628 5485 5484 5633 5634 5490 5629 5486 5485 5634 5635 5491 5630 5487 5486 5635 5636 5492 5631 5488 5487 5636 5637 5493 5632 5489 5488 5637 5638 5494 5633 5490 5489 5638 5639 5061 5634 5491 5490 5639 5640 5062 5492 5491 5635 5641 5498 5640 5493 5492 5636 5641 5642 5499 5494 5493 5637 5642 5643 5353 5061 5494 5638 5643 5644 5354 5061 5639 5062 5644 5502 5503 5062 5640 5498 5502 5645 5356 5499 5498 5641 5645 5646 5357 5499 5642 5353 5646 5506 5507 5353 5643 5354 5506 5358 5508 5503 5354 5644 5359 5647 5648 5503 5502 5356 5359 5361 5509 5356 5645 5357 5362 5649 5650 5357 5646 5507 5362 5651 5364 5506 5508 5507 5651 5512 5220 5508 5358 5360 5513 5511 5652 5359 5509 5360 5513 5653 5366 5361 5363 5509 5653 5516 5224 5362 5364 5363 5517 5515 5654 5651 5220 5364 5519 5655 5656 5512 5221 5220 5518 5657 5369 5366 5221 5513 5657 5370 5521 5653 5224 5366 5371 5520 5658 5516 5225 5224 5522 5658 5659 5368 5225 5517 5523 5659 5660 5369 5368 5518 5660 5661 5524 5521 5369 5657 5526 5662 5663 5229 5521 5370 5525 5664 5376 5230 5229 5371 5664 5528 5377 5373 5230 5522 5528 5378 5530 5374 5373 5523 5379 5529 5665 5375 5374 5524 5381 5665 5666 5376 5375 5525 5531 5666 5667 5377 5376 5664 5532 5667 5668 5530 5377 5528 5533 5668 5669 5380 5530 5378 5534 5669 5670 5238 5380 5379 5536 5671 5672 5239 5238 5381 5535 5673 5386 5241 5239 5531 5673 5387 5538 5532 5383 5241 5388 5537 5674 5533 5384 5383 5539 5674 5675 5385 5384 5534 5676 5677 5678 5386 5385 5535 5540 5391 5541 5673 5538 5386 5392 5676 5679 5387 5246 5538 5542 5679 5680 5388 5247 5246 5542 5395 5543 5539 5390 5247 5396 5681 5682 5540 5541 5390 5683 5684 5685 5391 5393 5541 5544 5545 5399 5393 5392 5394 5686 5687 5688 5542 5543 5394 5546 5547 5401 5543 5395 5397 5689 5690 5691 5396 5398 5397 5548 5552 5405 5398 5544 5399 5552 5403 5549 5399 5545 5400 5404 168 5692 5400 5546 5401 5404 174 162 5547 5402 5401 5403 5552 5689 5402 5548 5405 5408 5556 5409 5555 5553 5409 170 5262 166 5549 5403 164 5553 5693 5554 164 5404 162 5554 5694 5558 170 162 174 5550 5555 182 5556 5408 175 5560 5557 5695 5559 5560 5696 5554 5558 5410 5555 5693 5553 5561 5414 5696 5693 5694 5554 5696 5560 5697 5558 5695 5557 5412 5562 5563 5562 5698 5699 5266 5414 5267 5414 5559 5696 4987 5564 5700 5564 4703 5415 5413 5412 5563 5564 5563 5701 4987 4703 5564 4983 5419 4986 5273 5272 4982 5702 5703 5704 5419 5565 5420 5272 5705 5565 5706 5707 5708 5705 5275 5566 5276 5425 5567 5274 5566 5275 5709 5279 5568 5567 5274 5276 5710 5711 5712 5567 5425 5568 706 5278 711 5709 5568 5425 710 5713 5569 5277 5279 5709 5713 5428 5570 711 5278 5277 5714 5715 5716 711 709 706 5429 5717 5432 707 706 709 5717 5572 5433 707 710 5569 5572 5571 5434 5569 5713 5570 5571 5575 5435 5570 5428 5430 5575 5574 5436 5430 5429 5432 5718 5719 5720 5717 5433 5432 5577 5578 5287 5433 5572 5434 5719 5579 5578 5571 5435 5434 5579 5581 5439 5575 5436 5435 5581 5580 5291 5436 5574 5437 5721 5583 5580 5577 5287 5437 5722 5586 5723 5578 5288 5287 5584 5585 5442 5439 5288 5579 5585 5443 5587 5581 5291 5439 5724 5444 5443 5580 5292 5291 5725 5588 5444 5583 5441 5292 5726 5727 5728 5442 5441 5584 5729 5593 5727 5587 5442 5585 5590 5592 5448 5297 5587 5443 5592 5591 5449 5298 5297 5444 5591 5450 5595 5588 5446 5298 5730 5451 5450 5589 5447 5446 5731 5453 5451 5448 5447 5590 5732 5596 5453 5449 5448 5592 5733 5597 5596 5595 5449 5591 5734 5598 5597 5452 5595 5450 5735 5599 5598 5305 5452 5451 5736 5602 5737 5306 5305 5453 5600 5601 5458 5308 5306 5596 5601 5459 5603 5597 5455 5308 5738 5460 5459 5598 5456 5455 5739 5462 5460 5599 5457 5456 5740 5604 5462 5458 5457 5600 5741 5742 5743 5603 5458 5601 5605 5466 5606 5459 5461 5603 5742 5467 5466 5460 5463 5461 5744 5607 5467 5462 5464 5463 5607 5609 5470 5604 5465 5464 5609 5608 5471 5605 5606 5465 5745 5746 5747 5466 5468 5606 5611 5612 5320 5468 5467 5469 5746 5613 5612 5607 5470 5469 5613 5614 5323 5470 5609 5471 5748 5615 5614 5471 5608 5472 5615 5616 5475 5472 5611 5320 5749 5750 5751 5320 5612 5321 5617 5752 5618 5321 5613 5323 5752 5619 5330 5324 5323 5614 5753 5754 5755 5324 5615 5475 5620 5756 5621 5475 5616 5476 5756 5757 5622 5618 5476 5617 5757 5758 5335 5330 5618 5752 5758 5759 5333 5330 5619 5328 5759 5760 5626 5621 5328 5620 5760 5761 5627 5622 5621 5756 5761 5762 5628 5335 5622 5757 5762 5763 5629 5333 5335 5758 5763 5764 5630 5759 5626 5333 5764 5765 5631 5760 5627 5626 5765 5766 5632 5761 5628 5627 5766 5767 5633 5762 5629 5628 5767 5768 5634 5763 5630 5629 5768 5769 5635 5764 5631 5630 5769 5770 5636 5765 5632 5631 5770 5771 5637 5766 5633 5632 5771 5772 5638 5767 5634 5633 5772 5773 5639 5768 5635 5634 5773 5774 5640 5769 5636 5635 5774 5495 5641 5637 5636 5770 5495 5497 5642 5638 5637 5771 5497 5775 5643 5639 5638 5772 5775 5500 5644 5640 5639 5773 5776 5777 5778 5640 5774 5641 5501 5779 5645 5642 5641 5495 5779 5504 5646 5643 5642 5497 5780 5505 5504 5643 5775 5644 5505 5647 5358 5502 5644 5500 5781 5648 5647 5502 5501 5645 5648 5649 5361 5645 5779 5646 5782 5650 5649 5646 5504 5506 5650 5510 5651 5506 5505 5358 5783 5511 5510 5358 5647 5359 5784 5785 5786 5648 5361 5359 5652 5514 5653 5361 5649 5362 5785 5515 5514 5650 5651 5362 5787 5654 5515 5510 5512 5651 5654 5655 5518 5511 5513 5512 5655 5519 5657 5652 5653 5513 5788 5520 5519 5514 5516 5653 5789 5658 5520 5515 5517 5516 5790 5659 5658 5518 5517 5654 5791 5792 5793 5657 5518 5655 5794 5663 5792 5370 5657 5519 5661 5662 5525 5371 5370 5520 5662 5526 5664 5658 5522 5371 5795 5527 5526 5659 5523 5522 5796 5529 5527 5660 5524 5523 5797 5665 5529 5525 5524 5661 5798 5666 5665 5664 5525 5662 5799 5667 5666 5528 5664 5526 5800 5668 5667 5378 5528 5527 5801 5802 5803 5379 5378 5529 5804 5672 5802 5381 5379 5665 5670 5671 5535 5531 5381 5666 5671 5536 5673 5667 5532 5531 5805 5537 5536 5668 5533 5532 5806 5674 5537 5669 5534 5533 5807 5678 5808 5535 5534 5670 5675 5677 5540 5673 5535 5671 5677 5676 5391 5536 5387 5673 5809 5679 5676 5537 5388 5387 5810 5811 5812 5674 5539 5388 5680 5681 5395 5675 5540 5539 5811 5682 5681 5677 5391 5540 5682 5684 5544 5676 5392 5391 5684 5683 5545 5392 5679 5542 5683 5687 5546 5680 5395 5542 5687 5686 5547 5395 5681 5396 5686 5690 5548 5682 5544 5396 5690 5689 5552 5544 5684 5545 5689 168 5403 5545 5683 5546 5813 5814 5815 5546 5687 5547 5692 5816 174 5547 5686 5548 5816 180 175 5690 5552 5548 5556 182 5555 5550 5693 5555 175 5408 170 5403 168 5404 5551 5694 5693 5404 5692 174 5694 5817 5695 174 5816 175 173 5550 177 182 5556 180 5696 5697 5818 5818 5698 5561 5694 5695 5558 5551 5693 5550 5697 5819 5818 5551 5817 5694 5699 5701 5562 5695 5820 5560 5821 5822 5699 5823 5700 5824 5414 5561 5412 5696 5818 5561 4984 5700 5823 5564 5701 5700 5563 5562 5701 5701 5824 5700 4987 5700 4984 4983 5272 5565 5825 5271 5273 5417 5271 5825 5565 5705 5566 5271 5826 5705 5827 5423 5276 5826 5827 5275 5828 5829 5830 5276 5275 5827 5831 5277 5709 5276 5423 5425 711 5277 5832 5709 5425 5424 718 5712 716 5709 5424 5831 5713 710 541 5277 5831 5832 5428 5713 540 711 5832 712 5429 5428 5833 709 712 719 5717 5429 5716 541 710 719 5572 5717 5715 540 5713 541 5834 5835 5573 5428 540 5833 5575 5571 5835 5716 5429 5833 5836 5837 5576 5717 5716 5715 5577 5574 5837 5715 5573 5572 5578 5577 5720 5571 5573 5835 5838 5839 5840 5835 5576 5575 5581 5579 5841 5574 5576 5837 5839 5721 5582 5577 5837 5720 5842 5722 5843 5720 5719 5578 5584 5583 5844 5719 5841 5579 5585 5584 5723 5841 5582 5581 5845 5724 5586 5582 5721 5580 5846 5725 5724 5721 5844 5583 5847 5726 5848 5844 5723 5584 5589 5588 5849 5586 5585 5723 5590 5589 5728 5724 5443 5586 5592 5590 5727 5724 5725 5444 5850 5594 5593 5725 5849 5588 5851 5730 5594 5849 5728 5589 5852 5731 5730 5728 5727 5590 5853 5732 5731 5593 5592 5727 5854 5733 5732 5594 5591 5593 5855 5856 5857 5730 5450 5594 5858 5859 5856 5731 5451 5730 5860 5736 5859 5732 5453 5731 5600 5599 5861 5733 5596 5732 5601 5600 5737 5733 5734 5597 5862 5738 5602 5734 5735 5598 5863 5739 5738 5735 5861 5599 5864 5740 5739 5861 5737 5600 5865 5741 5866 5602 5601 5737 5605 5604 5867 5738 5459 5602 5466 5605 5743 5738 5739 5460 5868 5744 5742 5739 5740 5462 5869 5870 5871 5740 5867 5604 5609 5607 5872 5605 5867 5743 5870 5873 5610 5743 5742 5466 5611 5608 5873 5742 5744 5467 5612 5611 5747 5607 5744 5872 5874 5875 5876 5872 5610 5609 5614 5613 5877 5608 5610 5873 5878 5879 5880 5611 5873 5747 5616 5615 5881 5612 5747 5746 5617 5616 5882 5613 5746 5877 5752 5617 5750 5614 5877 5748 5619 5752 5749 5881 5615 5748 5620 5619 5883 5616 5881 5882 5756 5620 5884 5750 5617 5882 5757 5756 5885 5749 5752 5750 5758 5757 5886 5883 5619 5749 5759 5758 5887 5883 5884 5620 5760 5759 5888 5885 5756 5884 5761 5760 5889 5886 5757 5885 5762 5761 5623 5887 5758 5886 5763 5762 5625 5888 5759 5887 5764 5763 5890 5888 5889 5760 5765 5764 5891 5889 5623 5761 5766 5765 5892 5623 5625 5762 5767 5766 5893 5625 5890 5763 5768 5767 5894 5890 5891 5764 5769 5768 5895 5891 5892 5765 5770 5769 5896 5892 5893 5766 5771 5770 5897 5893 5894 5767 5772 5771 5898 5894 5895 5768 5773 5772 5899 5895 5896 5769 5774 5773 5900 5896 5897 5770 5495 5774 5901 5897 5898 5771 5902 5903 5904 5899 5772 5898 5775 5497 5905 5900 5773 5899 5500 5775 5906 5901 5774 5900 5501 5500 5907 5495 5901 5496 5779 5501 5778 5905 5497 5496 5504 5779 5777 5906 5775 5905 5908 5909 5910 5500 5906 5907 5647 5505 5911 5778 5501 5907 5912 5913 5914 5779 5778 5777 5649 5648 5915 5504 5777 5780 5916 5917 5918 5505 5780 5911 5510 5650 5919 5647 5911 5781 5917 5920 5783 5648 5781 5915 5652 5511 5920 5915 5782 5649 5514 5652 5786 5650 5782 5919 5921 5787 5785 5919 5783 5510 5922 5923 5924 5783 5920 5511 5655 5654 5925 5652 5920 5786 5923 5788 5656 5786 5785 5514 5926 5789 5788 5785 5787 5515 5927 5790 5789 5787 5925 5654 5928 5791 5929 5656 5655 5925 5660 5659 5930 5788 5519 5656 5661 5660 5793 5789 5520 5788 5662 5661 5792 5789 5790 5658 5931 5795 5663 5790 5930 5659 5932 5796 5795 5930 5793 5660 5933 5797 5796 5793 5792 5661 5934 5798 5797 5663 5662 5792 5935 5799 5798 5795 5526 5663 5936 5937 5938 5796 5527 5795 5939 5801 5937 5797 5529 5796 5669 5668 5940 5798 5665 5797 5670 5669 5803 5799 5666 5798 5671 5670 5802 5799 5800 5667 5941 5805 5672 5800 5940 5668 5942 5806 5805 5940 5803 5669 5943 5807 5944 5803 5802 5670 5675 5674 5945 5672 5671 5802 5677 5675 5808 5672 5805 5536 5946 5809 5678 5805 5806 5537 5947 5810 5948 5806 5945 5674 5680 5679 5949 5945 5808 5675 5681 5680 5812 5808 5678 5677 5950 5951 5952 5678 5809 5676 5684 5682 5953 5679 5809 5949 5951 5954 5685 5680 5949 5812 5687 5683 5954 5681 5812 5811 5955 5956 5688 5682 5811 5953 5690 5686 5956 5684 5953 5685 5957 5958 5959 5683 5685 5954 168 5689 169 5687 5954 5688 5692 168 167 5686 5688 5956 5816 5692 5815 5690 5956 5691 180 5816 5814 169 5689 5691 5960 171 176 5817 5551 172 180 5556 175 167 5815 5692 5820 5817 5961 5815 5814 5816 173 176 171 5814 181 180 5697 5962 5819 177 182 181 5818 5819 5963 5820 5697 5560 5817 5820 5695 173 172 5551 5821 5698 5963 172 5961 5817 5964 5963 5819 5697 5820 5962 5699 5822 5824 5822 5965 5966 5561 5698 5562 5698 5818 5963 5273 5823 5967 4982 4984 5823 5701 5699 5824 5823 5824 5968 5273 4982 5823 5272 5271 5705 5418 5417 5825 5416 5969 5417 5705 5826 5275 5417 5970 5826 5971 5972 5423 5971 5827 5970 5972 5973 5424 5423 5827 5971 5710 5832 5831 5424 5423 5972 712 5832 5712 5424 5973 5831 719 763 541 5710 5831 5973 5974 5975 5976 5710 5712 5832 540 5977 5833 712 5712 718 5833 5978 5716 763 719 718 5979 5980 5714 539 541 763 5715 5980 5573 5977 540 539 5981 5982 5983 5833 5977 5978 5835 5984 5576 5714 5716 5978 5985 5986 5987 5715 5714 5980 5837 5988 5720 5573 5980 5834 5985 5989 5718 5835 5834 5984 5719 5989 5841 5984 5836 5576 5841 5840 5582 5837 5836 5988 5990 5839 5991 5720 5988 5718 5721 5990 5844 5718 5989 5719 5844 5843 5723 5841 5989 5840 5992 5845 5722 5840 5839 5582 5846 5845 5993 5839 5990 5721 5847 5994 5995 5990 5843 5844 5725 5996 5849 5843 5722 5723 5849 5848 5728 5722 5845 5586 5997 5729 5726 5845 5846 5724 5998 5850 5729 5846 5996 5725 5851 5850 5999 5996 5848 5849 5852 5851 6000 5848 5726 5728 5853 5852 6001 5726 5729 5727 6002 6003 6004 5850 5593 5729 5855 6002 6005 5851 5594 5850 5733 6006 5734 5852 5730 5851 5734 5857 5735 5853 5731 5852 5735 5856 5861 5854 5732 5853 5861 5859 5737 5854 6006 5733 6007 5862 5736 6006 5857 5734 5863 5862 6008 5857 5856 5735 5864 5863 6009 5856 5859 5861 5865 6010 6011 5859 5736 5737 5740 6012 5867 5862 5602 5736 5867 5866 5743 5862 5863 5738 6013 5868 5741 5863 5864 5739 5869 6014 6015 5864 6012 5740 5744 6016 5872 6012 5866 5867 5872 5871 5610 5743 5866 5741 6017 6018 6019 5741 5868 5742 5873 6020 5747 5744 5868 6016 6017 6021 5745 5872 6016 5871 5746 6021 5877 5871 5870 5610 5877 5876 5748 5873 5870 6020 5748 5875 5881 5747 6020 5745 5881 5880 5882 5746 5745 6021 5882 5879 5750 5876 5877 6021 6022 6023 6024 5748 5876 5875 5749 6025 5883 5880 5881 5875 5883 6026 5884 5879 5882 5880 5885 5884 6027 5751 5750 5879 5885 5754 5886 6025 5749 5751 5886 5753 5887 6026 5883 6025 5887 6028 5888 6026 6027 5884 5888 6029 5889 6027 5754 5885 5623 5889 6030 5753 5886 5754 6031 6032 6033 6028 5887 5753 5625 6034 5890 6029 5888 6028 5890 6033 5891 6029 6030 5889 5891 6032 5892 6030 5624 5623 5892 6035 5893 5624 6034 5625 5893 6036 5894 6034 6033 5890 5894 6037 5895 6033 6032 5891 5895 6038 5896 6032 6035 5892 5896 6039 5897 6035 6036 5893 5897 6040 5898 6036 6037 5894 5898 6041 5899 6037 6038 5895 5899 6042 5900 6038 6039 5896 5900 6043 5901 6039 6040 5897 5901 6044 5496 6040 6041 5898 5496 6045 5905 6042 5899 6041 5905 5904 5906 6043 5900 6042 5906 5903 5907 6044 5901 6043 5907 6046 5778 6044 6045 5496 6047 6048 6049 5904 5905 6045 5777 6050 5780 5903 5906 5904 5780 6051 5911 5907 5903 6046 5911 5910 5781 5776 5778 6046 5781 5909 5915 5777 5776 6050 5915 5914 5782 5780 6050 6051 5782 5913 5919 5911 6051 5910 5919 5918 5783 5781 5910 5909 6052 6053 6054 5915 5909 5914 5920 6055 5786 5782 5914 5913 6052 5921 5784 5919 5913 5918 5922 6056 6057 5918 5917 5783 5787 6058 5925 5917 6055 5920 5925 5924 5656 5786 6055 5784 5926 5923 6059 5784 5921 5785 6060 6061 6062 5921 6058 5787 5928 6060 6063 6058 5924 5925 5790 6064 5930 5924 5923 5656 5930 5929 5793 5923 5926 5788 6065 5794 5791 5926 5927 5789 6066 5931 5794 5927 6064 5790 5932 5931 6067 6064 5929 5930 5933 5932 6068 5929 5791 5793 6069 6070 6071 5791 5794 5792 6072 6069 6073 5931 5663 5794 5936 6072 6074 5932 5795 5931 5799 6075 5800 5933 5796 5932 5800 5938 5940 5934 5797 5933 5940 5937 5803 5934 5935 5798 6076 5804 5801 5935 6075 5799 6077 5941 5804 6075 5938 5800 5942 5941 6078 5938 5937 5940 5943 6079 6080 5937 5801 5803 5806 6081 5945 5801 5804 5802 5945 5944 5808 5804 5941 5672 6082 5946 5807 5941 5942 5805 6083 5946 6084 5942 6081 5806 5809 6083 5949 6081 5944 5945 5949 5948 5812 5808 5944 5807 6085 6086 5810 5807 5946 5678 5811 6086 5953 5946 6083 5809 5953 5952 5685 5949 6083 5948 6087 6088 6089 5812 5948 5810 5954 6090 5688 5811 5810 6086 6091 6092 6093 5953 6086 5952 5956 6094 5691 5685 5952 5951 5691 6095 169 5954 5951 6090 169 5959 167 5688 6090 5955 167 5958 5815 6094 5956 5955 6096 6097 6098 5691 6094 6095 5814 6099 181 5959 169 6095 181 6100 177 5959 5958 167 177 5550 182 5813 5815 5958 172 179 5961 6099 5814 5813 5961 6101 5962 6100 181 6099 178 171 5960 177 6100 176 5964 5819 6102 6103 5963 5964 5961 5962 5820 171 179 172 5965 5821 6103 179 6101 5961 6103 5964 6104 5962 6102 5819 5822 5966 5968 6105 6106 5967 5698 5821 5699 5821 5963 6103 5825 5967 6106 5823 5968 5967 5824 5822 5968 5968 6105 5967 5273 5967 5825 5271 5417 5826 6107 5969 5416 6107 5706 5969 5826 5970 5827 5969 6108 5970 5972 6109 6110 6109 5971 6108 6110 6111 5973 6109 5972 5971 6112 6113 6114 5973 5972 6110 6115 727 720 6111 5710 5973 763 6116 539 5711 5710 6111 5977 539 6117 716 5712 5711 5977 5976 5978 715 718 716 5978 5975 5714 6116 763 715 6118 6119 6120 6117 539 6116 5980 6121 5834 5976 5977 6117 5834 6122 5984 5978 5976 5975 5984 5982 5836 5979 5714 5975 5836 5981 5988 5980 5979 6121 5988 5986 5718 6122 5834 6121 6123 6124 6125 5984 6122 5982 5989 6126 5840 5836 5982 5981 6124 5991 5838 5988 5981 5986 6127 6128 6129 5718 5986 5985 5990 6130 5843 5989 5985 6126 6127 5992 5842 5840 6126 5838 6131 5993 5992 5838 5991 5839 5995 6132 6133 5991 6130 5990 5846 6134 5996 6130 5842 5843 5996 5994 5848 5722 5842 5992 6135 5997 5847 5992 5993 5845 6136 5998 5997 5993 6134 5846 6137 5999 5998 6134 5994 5996 6138 6139 6140 5994 5847 5848 6141 6138 6142 5847 5997 5726 6004 6141 6143 5997 5998 5729 5853 6144 5854 5998 5999 5850 5854 6003 6006 6000 5851 5999 6006 6002 5857 6000 6001 5852 6145 5858 5855 6001 6144 5853 6146 5860 5858 6144 6003 5854 6147 6007 5860 6003 6002 6006 6148 6008 6007 6002 5855 5857 6149 6150 6151 5855 5858 5856 6011 6149 6152 5858 5860 5859 5864 6153 6012 5860 6007 5736 6012 6010 5866 5862 6007 6008 6154 6013 5865 6008 6009 5863 6155 6156 6013 6009 6153 5864 5868 6156 6016 6153 6010 6012 6016 6014 5871 5866 6010 5865 6157 6158 5869 5741 5865 6013 5870 6158 6020 6013 6156 5868 6020 6018 5745 6016 6156 6014 6159 6160 6161 5871 6014 5869 6021 6162 5876 5870 5869 6158 6160 6163 5874 6020 6158 6018 5875 6163 5880 6017 5745 6018 6164 6165 6166 6021 6017 6162 5879 6167 5751 5874 5876 6162 6025 5751 6168 5875 5874 6163 6025 6024 6026 5878 5880 6163 6026 6023 6027 6167 5879 5878 5754 6027 6169 6167 6168 5751 6170 6171 6172 6024 6025 6168 5753 6173 6028 6023 6026 6024 6028 6174 6029 6023 6169 6027 6029 6175 6030 6169 5755 5754 5624 6030 6176 5755 6173 5753 6034 5624 6177 6173 6174 6028 6033 6034 6178 6175 6029 6174 6179 6035 6032 6175 6176 6030 6180 6036 6035 6176 6177 5624 6181 6037 6036 6177 6178 6034 6182 6038 6037 6178 6031 6033 6183 6039 6038 6031 6179 6032 6184 6040 6039 6179 6180 6035 6185 6186 6187 6180 6181 6036 6040 6188 6041 6181 6182 6037 6041 6187 6042 6182 6183 6038 6042 6186 6043 6183 6184 6039 6043 6189 6044 6184 6188 6040 6044 6190 6045 6188 6187 6041 5904 6045 6191 6187 6186 6042 6192 6193 6194 6189 6043 6186 5903 6195 6046 6190 6044 6189 6046 6196 5776 6190 6191 6045 6050 5776 6197 5902 5904 6191 6050 6049 6051 6195 5903 5902 6051 6048 5910 6196 6046 6195 6198 6199 5908 6197 5776 6196 5909 6199 5914 6049 6050 6197 6200 6201 5912 6051 6049 6048 5913 6201 5918 5908 5910 6048 6202 6203 5916 5909 5908 6199 5917 6203 6055 5914 6199 5912 6055 6053 5784 5913 5912 6201 6204 6205 6052 5918 6201 5916 5921 6205 6058 5916 6203 5917 6058 6056 5924 6055 6203 6053 6206 6059 5922 5784 6053 6052 6207 6062 6208 6052 6205 5921 5926 6209 5927 6205 6056 6058 5927 6061 6064 6056 5922 5924 6064 6060 5929 5923 5922 6059 6210 6065 5928 6059 6209 5926 6211 6066 6065 6209 6061 5927 6212 6067 6066 6061 6060 6064 6213 6214 6215 6060 5928 5929 6071 6213 6216 5928 6065 5791 5933 6217 5934 6065 6066 5794 5934 6070 5935 6067 5931 6066 5935 6069 6075 6068 5932 6067 6075 6072 5938 6068 6217 5933 6218 5939 5936 6217 6070 5934 6219 6076 5939 6070 6069 5935 6220 6077 6076 6069 6072 6075 6221 6078 6077 6072 5936 5938 6080 6222 6223 5936 5939 5937 5942 6224 6081 5939 6076 5801 6081 6079 5944 5804 6076 6077 6225 6082 5943 6077 6078 5941 6226 6084 6082 6078 6224 5942 6227 6228 6229 6224 6079 6081 6083 6230 5948 5944 6079 5943 6227 6085 5947 5807 5943 6082 6231 6232 6233 6082 6084 5946 6086 6234 5952 6083 6084 6230 6232 6235 5950 5948 6230 5947 5951 6235 6090 5810 5947 6085 6090 6088 5955 6086 6085 6234 5955 6087 6094 5952 6234 5950 6094 6092 6095 5951 5950 6235 6095 6091 5959 6088 6090 6235 6236 6237 5957 5955 6088 6087 5958 6237 5813 6092 6094 6087 6099 5813 6238 6095 6092 6091 6099 6098 6100 5957 5959 6091 6100 6097 176 6237 5958 5957 185 6239 6240 5813 6237 6238 179 187 6101 6099 6238 6098 6101 6241 6102 6100 6098 6097 178 6242 186 176 6097 5960 6104 5964 6243 6103 6104 6244 6101 6102 5962 178 187 179 6245 5965 6244 187 6241 6101 6246 6105 5966 6102 6243 5964 6246 6247 6248 6249 6106 6250 5821 5965 5822 5965 6103 6244 6246 5966 6245 5416 5418 6106 5968 5966 6105 6105 6250 6106 5825 6106 5418 5417 5969 5970 5707 5706 6107 6251 6252 6253 5970 6108 5971 5706 6254 6108 6110 6255 5830 6254 6255 6109 5830 6256 6111 6110 6109 6255 6257 716 5711 6110 5830 6111 715 721 6116 5711 6111 6256 6116 6258 6117 6257 5711 6256 5976 6117 6259 717 716 6257 6260 6261 6262 721 715 717 5975 6263 5979 6258 6116 721 6121 5979 6264 6259 6117 6258 6121 6120 6122 5974 5976 6259 5982 6122 6119 6263 5975 5974 6265 6266 5983 6264 5979 6263 5981 6266 5986 6120 6121 6264 6267 6268 5987 6119 6122 6120 6126 5985 6268 5982 6119 5983 6126 6125 5838 5981 5983 6266 6269 6270 6129 5986 6266 5987 5991 6271 6130 5985 5987 6268 6130 6128 5842 6126 6268 6125 6272 6131 6127 5838 6125 6124 6273 6133 6274 5991 6124 6271 5993 6275 6134 6271 6128 6130 6134 6132 5994 5842 6128 6127 6276 6135 5995 5992 6127 6131 6277 6136 6135 6131 6275 5993 6278 6137 6136 6275 6132 6134 6279 6280 6140 6132 5995 5994 6000 5999 6281 5995 6135 5847 6000 6139 6001 6135 6136 5997 6001 6138 6144 6136 6137 5998 6144 6141 6003 5999 6137 6281 6282 6005 6004 6281 6139 6000 6283 6145 6005 6139 6138 6001 6284 6146 6145 6138 6141 6144 6285 6147 6146 6141 6004 6003 6286 6148 6147 6004 6005 6002 6287 6288 6151 6005 6145 5855 6009 6008 6289 6145 6146 5858 6009 6150 6153 6146 6147 5860 6153 6149 6010 6007 6147 6148 6290 6154 6011 6008 6148 6289 6291 6155 6154 6289 6150 6009 6292 6293 6294 6150 6149 6153 6156 6295 6014 6010 6149 6011 6293 6157 6015 5865 6011 6154 6296 6297 6298 6013 6154 6155 6158 6299 6018 6156 6155 6295 6297 6300 6019 6014 6295 6015 6162 6017 6300 5869 6015 6157 6162 6161 5874 6158 6157 6299 6301 6302 6303 6018 6299 6019 6163 6304 5878 6300 6017 6019 6167 5878 6305 6162 6300 6161 6167 6166 6168 6160 5874 6161 6024 6168 6165 6304 6163 6160 6306 6307 6308 6305 5878 6304 6023 6309 6169 6166 6167 6305 5755 6169 6310 6166 6165 6168 6173 5755 6311 6022 6024 6165 6173 6172 6174 6309 6023 6022 6174 6171 6175 6309 6310 6169 6175 6312 6176 6310 6311 5755 6177 6176 6313 6311 6172 6173 6178 6177 6314 6172 6171 6174 6031 6178 6315 6171 6312 6175 6179 6031 6316 6176 6312 6313 6180 6179 6317 6177 6313 6314 6181 6180 6318 6178 6314 6315 6182 6181 6319 6031 6315 6316 6183 6182 6320 6179 6316 6317 6184 6183 6321 6180 6317 6318 6188 6184 6322 6181 6318 6319 6187 6188 6323 6319 6320 6182 6324 6325 6326 6320 6321 6183 6186 6327 6189 6321 6322 6184 6189 6328 6190 6322 6323 6188 6190 6329 6191 6323 6185 6187 5902 6191 6330 6185 6327 6186 6195 5902 6331 6328 6189 6327 6195 6194 6196 6329 6190 6328 6196 6193 6197 6329 6330 6191 6049 6197 6332 6330 6331 5902 6333 6334 6047 6194 6195 6331 6048 6334 5908 6193 6196 6194 6335 6336 6337 6332 6197 6193 6199 6338 5912 6047 6049 6332 6339 6340 6341 6048 6047 6334 6201 6342 5916 6198 5908 6334 6343 6344 6345 6199 6198 6338 6203 6346 6053 6200 5912 6338 6344 6204 6054 6201 6200 6342 6347 6348 6349 5916 6342 6202 6205 6350 6056 6203 6202 6346 6348 6206 6057 6053 6346 6054 6351 6352 6207 6052 6054 6204 6209 6059 6353 6204 6350 6205 6209 6208 6061 6056 6350 6057 6354 6063 6062 5922 6057 6206 6355 6210 6063 6059 6206 6353 6356 6211 6210 6353 6208 6209 6357 6358 6359 6208 6062 6061 6360 6215 6359 6062 6063 6060 6067 6361 6068 6063 6210 5928 6068 6214 6217 6210 6211 6065 6217 6213 6070 6066 6211 6212 6362 6073 6071 6212 6361 6067 6363 6074 6073 6361 6214 6068 6364 6218 6074 6214 6213 6217 6365 6219 6218 6213 6071 6070 6366 6220 6219 6071 6073 6069 6367 6368 6369 6073 6074 6072 6370 6223 6369 6074 6218 5936 6078 6371 6224 6218 6219 5939 6224 6222 6079 6076 6219 6220 6372 6225 6080 6077 6220 6221 6373 6226 6225 6221 6371 6078 6374 6375 6229 6371 6222 6224 6084 6376 6230 6222 6080 6079 6230 6228 5947 5943 6080 6225 6377 6378 6227 6082 6225 6226 6234 6085 6378 6226 6376 6084 6234 6233 5950 6230 6376 6228 6379 6380 6381 5947 6228 6227 6235 6382 6088 6378 6085 6227 6380 6383 6089 6234 6378 6233 6087 6383 6092 6232 5950 6233 6384 6385 6093 6235 6232 6382 6091 6385 5957 6089 6088 6382 6386 6387 6388 6383 6087 6089 6237 6389 6238 6093 6092 6383 6098 6238 6390 6385 6091 6093 6391 6392 6393 6236 5957 6385 6097 6394 5960 6389 6237 6236 5960 6242 178 6390 6238 6389 6240 6241 187 6096 6098 6390 6241 6239 6243 6097 6096 6394 6395 186 6392 6394 6242 5960 6396 6104 6397 6398 6247 6245 6241 6243 6102 6240 187 186 6396 190 6398 6240 6239 6241 6248 6250 6246 6243 6397 6104 6104 6396 6244 6248 6399 6400 5965 6245 5966 6245 6244 6398 6107 6249 6401 6249 5416 6106 6105 6246 6250 6249 6250 6402 6107 5416 6249 5969 5706 6108 5704 5708 5707 5703 5708 5704 6108 6254 6109 6254 5708 6403 6252 6404 6405 6403 5828 6255 5829 6112 6256 5830 6255 5828 6115 717 6257 5829 6256 5830 721 762 6258 6256 6112 6257 6258 6406 6259 6115 6257 6112 5974 6259 6407 6115 720 717 6263 5974 6408 762 721 720 6263 6262 6264 6406 6258 762 6120 6264 6261 6406 6407 6259 6409 6410 6411 6408 5974 6407 5983 6119 6412 6262 6263 6408 6413 6414 6415 6261 6264 6262 6266 6416 5987 6118 6120 6261 6417 6418 6419 6412 6119 6118 6125 6268 6420 6265 5983 6412 6419 6421 6123 6416 6266 6265 6271 6124 6421 5987 6416 6267 6128 6271 6269 6420 6268 6267 6422 6272 6129 6125 6420 6123 6423 6424 6273 6124 6123 6421 6275 6131 6425 6271 6421 6269 6275 6274 6132 6128 6269 6129 6426 6276 6133 6127 6129 6272 6427 6277 6276 6131 6272 6425 6428 6429 6430 6425 6274 6275 6430 6431 6280 6274 6133 6132 6281 6137 6432 6133 6276 5995 6139 6281 6279 6135 6276 6277 6433 6142 6140 6136 6277 6278 6434 6143 6142 6137 6278 6432 6435 6282 6143 6281 6432 6279 6436 6283 6282 6279 6140 6139 6437 6284 6283 6140 6142 6138 6438 6285 6284 6142 6143 6141 6439 6440 6441 6143 6282 6004 6441 6442 6288 6282 6283 6005 6289 6148 6443 6283 6284 6145 6150 6289 6287 6146 6284 6285 6444 6152 6151 6147 6285 6286 6445 6290 6152 6148 6286 6443 6446 6291 6290 6289 6443 6287 6447 6448 6292 6287 6151 6150 6295 6155 6449 6151 6152 6149 6295 6294 6015 6011 6152 6290 6450 6451 6293 6154 6290 6291 6299 6157 6451 6155 6291 6449 6299 6298 6019 6295 6449 6294 6452 6453 6297 6015 6294 6293 6161 6300 6453 6451 6157 6293 6454 6455 6159 6299 6451 6298 6304 6160 6455 6019 6298 6297 6304 6303 6305 6453 6300 6297 6166 6305 6302 6159 6161 6453 6456 6457 6164 6455 6160 6159 6022 6165 6457 6303 6304 6455 6309 6022 6458 6302 6305 6303 6309 6308 6310 6164 6166 6302 6311 6310 6307 6164 6457 6165 6172 6311 6459 6457 6458 6022 6460 6461 6462 6308 6309 6458 6171 6463 6312 6308 6307 6310 6312 6464 6313 6307 6459 6311 6314 6313 6465 6459 6170 6172 6315 6314 6466 6170 6463 6171 6316 6315 6467 6463 6464 6312 6317 6316 6468 6313 6464 6465 6318 6317 6469 6314 6465 6466 6319 6318 6470 6315 6466 6467 6320 6319 6471 6316 6467 6468 6321 6320 6472 6317 6468 6469 6322 6321 6473 6318 6469 6470 6323 6322 6474 6319 6470 6471 6185 6323 6475 6320 6471 6472 6327 6185 6476 6321 6472 6473 6328 6327 6477 6473 6474 6322 6328 6478 6329 6474 6475 6323 6329 6479 6330 6475 6476 6185 6331 6330 6480 6476 6477 6327 6194 6331 6481 6477 6478 6328 6482 6483 6484 6479 6329 6478 6193 6485 6332 6479 6480 6330 6047 6332 6486 6480 6481 6331 6487 6488 6489 6192 6194 6481 6334 6490 6198 6485 6193 6192 6338 6198 6491 6486 6332 6485 6338 6337 6200 6333 6047 6486 6342 6200 6336 6334 6333 6490 6342 6341 6202 6491 6198 6490 6346 6202 6340 6338 6491 6337 6346 6345 6054 6336 6200 6337 6492 6493 6347 6342 6336 6341 6350 6204 6494 6202 6341 6340 6350 6349 6057 6346 6340 6345 6495 6496 6348 6054 6345 6344 6353 6206 6496 6204 6344 6494 6208 6353 6351 6350 6494 6349 6497 6354 6207 6057 6349 6348 6498 6355 6354 6206 6348 6496 6499 6500 6501 6353 6496 6351 6501 6502 6358 6351 6207 6208 6212 6211 6503 6207 6354 6062 6361 6212 6357 6354 6355 6063 6361 6359 6214 6210 6355 6356 6504 6216 6215 6211 6356 6503 6505 6362 6216 6212 6503 6357 6506 6363 6362 6357 6359 6361 6507 6364 6363 6359 6215 6214 6508 6365 6364 6215 6216 6213 6509 6510 6511 6216 6362 6071 6511 6512 6368 6362 6363 6073 6221 6220 6513 6363 6364 6074 6371 6221 6367 6364 6365 6218 6371 6369 6222 6219 6365 6366 6514 6372 6223 6220 6366 6513 6515 6373 6372 6221 6513 6367 6516 6517 6375 6367 6369 6371 6376 6226 6518 6369 6223 6222 6376 6374 6228 6080 6223 6372 6519 6377 6229 6225 6372 6373 6520 6521 6522 6226 6373 6518 6233 6378 6523 6374 6376 6518 6522 6524 6231 6228 6374 6229 6382 6232 6524 6227 6229 6377 6382 6381 6089 6523 6378 6377 6525 6526 6527 6233 6523 6231 6093 6383 6528 6524 6232 6231 6529 6530 6531 6382 6524 6381 6385 6532 6236 6380 6089 6381 6389 6236 6533 6528 6383 6380 6389 6388 6390 6384 6093 6528 6096 6390 6387 6532 6385 6384 6394 6096 6534 6533 6236 6532 6394 6393 6242 6388 6389 6533 6242 6392 186 6388 6387 6390 6240 186 6395 6096 6387 6534 184 6397 6239 6394 6534 6393 6396 217 190 6242 6393 6392 6398 190 6535 6535 6399 6247 6239 6397 6243 185 6240 6395 6396 6398 6244 185 184 6239 192 6535 190 6396 6397 217 6248 6400 6402 6400 6536 6537 6245 6247 6246 6247 6398 6535 5707 6401 6538 6249 6402 6401 6250 6248 6402 6401 6402 6539 6107 6401 5707 5708 6254 5706 6540 5703 5702 6540 6541 5703 6254 6403 6255 5703 6542 6403 6543 6113 5829 6542 6543 5828 735 6544 6545 5829 5828 6543 6546 729 733 5829 6113 6112 6406 762 6547 6114 6115 6112 6406 723 6407 727 6115 6114 6408 6407 722 727 726 720 6262 6408 6548 726 6547 762 6549 6550 6260 723 6406 6547 6118 6261 6550 723 722 6407 6412 6118 6551 6548 6408 722 6265 6412 6409 6260 6262 6548 6416 6265 6411 6550 6261 6260 6267 6416 6413 6551 6118 6550 6420 6267 6415 6409 6412 6551 6123 6420 6417 6411 6265 6409 6552 6553 6554 6413 6416 6411 6269 6421 6555 6415 6267 6413 6270 6554 6422 6417 6420 6415 6556 6557 6424 6123 6417 6419 6425 6272 6558 6421 6419 6555 6274 6425 6423 6270 6269 6555 6559 6426 6273 6129 6270 6422 6560 6427 6426 6272 6422 6558 6561 6562 6429 6425 6558 6423 6278 6277 6563 6423 6273 6274 6432 6278 6428 6273 6426 6133 6279 6432 6430 6276 6426 6427 6280 6564 6433 6277 6427 6563 6565 6434 6433 6278 6563 6428 6566 6435 6434 6432 6428 6430 6567 6436 6435 6279 6430 6280 6568 6569 6570 6280 6433 6140 6570 6571 6572 6433 6434 6142 6572 6573 6440 6434 6435 6143 6286 6285 6574 6435 6436 6282 6443 6286 6439 6436 6437 6283 6287 6443 6441 6284 6437 6438 6288 6575 6444 6285 6438 6574 6576 6445 6444 6286 6574 6439 6577 6446 6445 6443 6439 6441 6578 6579 6448 6287 6441 6288 6449 6291 6580 6288 6444 6151 6294 6449 6447 6152 6444 6445 6581 6450 6292 6290 6445 6446 6582 6583 6584 6291 6446 6580 6298 6451 6585 6447 6449 6580 6584 6452 6296 6294 6447 6292 6586 6587 6588 6293 6292 6450 6159 6453 6589 6585 6451 6450 6590 6591 6592 6298 6585 6296 6303 6455 6593 6452 6297 6296 6594 6595 6596 6589 6453 6452 6164 6302 6597 6454 6159 6589 6598 6599 6600 6593 6455 6454 6458 6457 6601 6301 6303 6593 6308 6458 6602 6301 6597 6302 6603 6604 6605 6456 6164 6597 6459 6307 6606 6456 6601 6457 6170 6459 6607 6601 6602 6458 6463 6170 6608 6306 6308 6602 6463 6609 6464 6306 6606 6307 6464 6610 6465 6606 6607 6459 6466 6465 6611 6607 6608 6170 6467 6466 6612 6608 6609 6463 6468 6467 6613 6609 6610 6464 6469 6468 6614 6465 6610 6611 6470 6469 6615 6466 6611 6612 6471 6470 6616 6467 6612 6613 6472 6471 6617 6468 6613 6614 6473 6472 6618 6469 6614 6615 6474 6473 6619 6470 6615 6616 6475 6474 6620 6471 6616 6617 6476 6475 6621 6472 6617 6618 6477 6476 6622 6473 6618 6619 6478 6477 6623 6474 6619 6620 6479 6478 6624 6620 6621 6475 6479 6324 6480 6621 6622 6476 6481 6480 6326 6622 6623 6477 6192 6481 6625 6623 6624 6478 6485 6192 6626 6324 6479 6624 6485 6484 6486 6324 6326 6480 6333 6486 6483 6326 6625 6481 6490 6333 6627 6626 6192 6625 6490 6489 6491 6484 6485 6626 6337 6491 6488 6484 6483 6486 6628 6629 6630 6627 6333 6483 6341 6336 6631 6489 6490 6627 6630 6632 6339 6488 6491 6489 6345 6340 6632 6335 6337 6488 6633 6634 6343 6631 6336 6335 6494 6344 6634 6341 6631 6339 6349 6494 6492 6632 6340 6339 6635 6495 6347 6345 6632 6343 6636 6637 6638 6344 6343 6634 6351 6496 6639 6492 6494 6634 6352 6638 6497 6349 6492 6347 6640 6498 6497 6348 6347 6495 6641 6642 6500 6496 6495 6639 6356 6355 6643 6351 6639 6352 6503 6356 6499 6352 6497 6207 6357 6503 6501 6354 6497 6498 6358 6644 6360 6355 6498 6643 6360 6645 6504 6356 6643 6499 6646 6505 6504 6503 6499 6501 6647 6506 6505 6357 6501 6358 6648 6507 6506 6359 6358 6360 6649 6650 6651 6360 6504 6215 6651 6652 6510 6504 6505 6216 6366 6365 6653 6505 6506 6362 6513 6366 6509 6506 6507 6363 6367 6513 6511 6364 6507 6508 6368 6654 6370 6365 6508 6653 6370 6655 6514 6366 6653 6509 6656 6515 6514 6513 6509 6511 6657 6658 6517 6367 6511 6368 6518 6373 6659 6369 6368 6370 6374 6518 6516 6223 6370 6514 6375 6660 6519 6372 6514 6515 6661 6662 6519 6373 6515 6659 6523 6377 6662 6518 6659 6516 6231 6523 6520 6375 6374 6516 6663 6664 6522 6229 6375 6519 6381 6524 6664 6662 6377 6519 6665 6666 6379 6520 6523 6662 6528 6380 6666 6231 6520 6522 6384 6528 6525 6664 6524 6522 6532 6384 6527 6381 6664 6379 6532 6531 6533 6666 6380 6379 6388 6533 6530 6666 6525 6528 6667 6668 6669 6527 6384 6525 6534 6387 6670 6531 6532 6527 6393 6534 6671 6531 6530 6533 198 200 6672 6386 6388 6530 6392 6673 6395 6386 6670 6387 185 6395 6674 6670 6671 6534 6675 195 6676 6393 6671 6391 6677 6678 6674 6391 6673 6392 6395 6673 6674 6679 6535 192 184 217 6397 183 185 6674 6536 6399 6679 183 201 184 6679 192 6680 217 191 190 6400 6537 6539 6681 6538 6682 6247 6399 6248 6399 6535 6679 5704 6538 6681 6401 6539 6538 6402 6400 6539 6539 6682 6538 5707 6538 5704 5708 5703 6403 6683 6541 6540 6683 6684 6541 6403 6542 5828 6541 6685 6542 6113 6686 6687 6686 6543 6685 6687 6688 6114 6113 6543 6686 6547 726 728 6687 6114 6113 723 6547 6689 6688 727 6114 6690 6691 6692 6688 725 727 6548 722 6693 725 728 726 6260 6548 6694 728 6689 6547 6695 6696 6697 724 723 6689 6551 6550 6698 724 6693 722 6409 6551 6699 6693 6694 6548 6410 6700 6701 6549 6260 6694 6413 6411 6701 6549 6698 6550 6414 6702 6703 6699 6551 6698 6417 6415 6703 6699 6410 6409 6418 6704 6705 6701 6411 6410 6555 6419 6705 6414 6413 6701 6270 6555 6552 6703 6415 6414 6554 6706 6707 6418 6417 6703 6558 6422 6707 6419 6418 6705 6423 6558 6556 6552 6555 6705 6424 6708 6559 6554 6270 6552 6709 6560 6559 6422 6554 6707 6710 6711 6712 6558 6707 6556 6563 6427 6713 6423 6556 6424 6428 6563 6561 6273 6424 6559 6429 6714 6431 6426 6559 6560 6431 6715 6564 6427 6560 6713 6564 6716 6565 6563 6713 6561 6717 6566 6565 6428 6561 6429 6718 6719 6720 6430 6429 6431 6721 6722 6718 6280 6431 6564 6437 6436 6723 6564 6565 6433 6438 6437 6568 6565 6566 6434 6574 6438 6570 6566 6567 6435 6439 6574 6572 6436 6567 6723 6440 6724 6442 6437 6723 6568 6442 6725 6575 6438 6568 6570 6575 6726 6576 6574 6570 6572 6727 6728 6729 6439 6572 6440 6730 6731 6727 6441 6440 6442 6580 6446 6732 6288 6442 6575 6447 6580 6578 6444 6575 6576 6448 6733 6581 6445 6576 6577 6734 6735 6736 6446 6577 6732 6585 6450 6737 6580 6732 6578 6296 6585 6582 6448 6447 6578 6738 6739 6584 6292 6448 6581 6589 6452 6739 6450 6581 6737 6454 6589 6586 6582 6585 6737 6593 6454 6588 6296 6582 6584 6301 6593 6590 6739 6452 6584 6597 6301 6592 6586 6589 6739 6456 6597 6594 6588 6454 6586 6601 6456 6596 6590 6593 6588 6602 6601 6598 6592 6301 6590 6306 6602 6600 6592 6594 6597 6606 6306 6740 6596 6456 6594 6607 6606 6603 6596 6598 6601 6608 6607 6605 6598 6600 6602 6609 6608 6741 6600 6740 6306 6610 6609 6742 6740 6603 6606 6610 6743 6611 6603 6605 6607 6612 6611 6744 6605 6741 6608 6613 6612 6745 6741 6742 6609 6614 6613 6746 6742 6743 6610 6615 6614 6747 6611 6743 6744 6616 6615 6748 6612 6744 6745 6617 6616 6749 6613 6745 6746 6618 6617 6750 6614 6746 6747 6619 6618 6751 6615 6747 6748 6620 6619 6752 6616 6748 6749 6621 6620 6753 6617 6749 6750 6622 6621 6754 6618 6750 6751 6623 6622 6755 6619 6751 6752 6624 6623 6756 6620 6752 6753 6324 6624 6757 6621 6753 6754 6758 6759 6760 6754 6755 6622 6625 6326 6761 6755 6756 6623 6626 6625 6762 6756 6757 6624 6484 6626 6763 6757 6325 6324 6764 6765 6766 6325 6761 6326 6627 6483 6767 6761 6762 6625 6489 6627 6768 6762 6763 6626 6769 6770 6771 6482 6484 6763 6335 6488 6772 6482 6767 6483 6631 6335 6773 6768 6627 6767 6339 6631 6628 6487 6489 6768 6774 6775 6776 6772 6488 6487 6343 6632 6777 6773 6335 6772 6778 6779 6780 6628 6631 6773 6492 6634 6781 6630 6339 6628 6493 6782 6635 6777 6632 6630 6783 6784 6785 6343 6777 6633 6639 6495 6786 6634 6633 6781 6352 6639 6636 6493 6492 6781 6638 6787 6640 6347 6493 6635 6788 6789 6790 6495 6635 6786 6643 6498 6791 6639 6786 6636 6499 6643 6641 6638 6352 6636 6500 6792 6502 6497 6638 6640 6502 6793 6644 6498 6640 6791 6644 6794 6645 6643 6791 6641 6645 6795 6646 6499 6641 6500 6796 6797 6798 6501 6500 6502 6799 6800 6796 6358 6502 6644 6801 6802 6799 6360 6644 6645 6508 6507 6803 6645 6646 6504 6653 6508 6649 6646 6647 6505 6509 6653 6651 6506 6647 6648 6510 6804 6512 6507 6648 6803 6512 6805 6654 6508 6803 6649 6654 6806 6655 6653 6649 6651 6655 6807 6656 6509 6651 6510 6808 6809 6810 6511 6510 6512 6659 6515 6811 6368 6512 6654 6516 6659 6657 6655 6370 6654 6517 6812 6660 6514 6655 6656 6660 6813 6661 6515 6656 6811 6814 6815 6816 6659 6811 6657 6520 6662 6817 6517 6516 6657 6521 6818 6663 6660 6375 6517 6819 6820 6821 6519 6660 6661 6379 6664 6822 6817 6662 6661 6823 6824 6665 6521 6520 6817 6525 6666 6824 6663 6522 6521 6526 6825 6826 6822 6664 6663 6531 6527 6826 6665 6379 6822 6827 6828 6529 6824 6666 6665 6386 6530 6828 6824 6526 6525 6670 6386 6829 6826 6527 6526 6671 6670 6667 6529 6531 6826 6391 6671 6669 6529 6828 6530 6673 6391 6830 6829 6386 6828 6673 6677 6674 6829 6667 6670 183 6674 6678 6667 6669 6671 201 183 6831 6830 6391 6669 200 6678 6832 6677 6673 6830 6680 192 6833 6679 6680 6834 201 191 217 183 6678 6831 6835 6536 6834 6831 202 201 6834 6680 193 191 6833 192 6836 6837 6838 6839 6681 6840 6399 6536 6400 6536 6679 6834 6836 6537 6835 5702 5704 6681 6539 6537 6682 6681 6682 6840 6540 5702 6681 5703 6541 6542 6841 6684 6683 6841 6404 6684 6542 6685 6543 6684 6842 6685 6687 6843 6544 6842 6843 6686 6544 734 6688 6686 6843 6687 6689 728 6844 6687 6544 6688 724 6689 6845 6688 734 725 6693 724 6846 734 729 725 6694 6693 6691 729 6844 728 6549 6694 6847 6844 6845 6689 6698 6549 6848 6846 724 6845 6699 6698 6696 6846 6691 6693 6410 6699 6849 6691 6847 6694 6850 6851 6852 6848 6549 6847 6414 6701 6853 6848 6696 6698 6854 6855 6856 6849 6699 6696 6418 6703 6857 6849 6700 6410 6858 6859 6860 6853 6701 6700 6552 6705 6861 6853 6702 6414 6862 6553 6860 6857 6703 6702 6863 6864 6865 6704 6418 6857 6556 6707 6866 6861 6705 6704 6867 6557 6865 6553 6552 6861 6868 6869 6870 6706 6554 6553 6869 6871 6712 6707 6706 6866 6713 6560 6872 6556 6866 6557 6561 6713 6711 6708 6424 6557 6873 6562 6710 6709 6559 6708 6874 6714 6873 6560 6709 6872 6875 6876 6877 6713 6872 6711 6876 6878 6879 6561 6711 6562 6880 6720 6878 6429 6562 6714 6567 6566 6881 6431 6714 6715 6723 6567 6719 6564 6715 6716 6568 6723 6722 6565 6716 6717 6882 6569 6721 6566 6717 6881 6883 6571 6882 6567 6881 6719 6884 6573 6883 6723 6719 6722 6885 6724 6884 6568 6722 6569 6886 6887 6888 6570 6569 6571 6887 6889 6729 6572 6571 6573 6577 6576 6890 6440 6573 6724 6732 6577 6728 6442 6724 6725 6578 6732 6731 6726 6575 6725 6891 6579 6730 6576 6726 6890 6892 6893 6736 6577 6890 6728 6737 6581 6894 6732 6728 6731 6582 6737 6735 6579 6578 6731 6895 6583 6734 6733 6448 6579 6896 6897 6898 6581 6733 6894 6586 6739 6899 6735 6737 6894 6900 6901 6902 6583 6582 6735 6590 6588 6903 6738 6584 6583 6904 6591 6902 6899 6739 6738 6594 6592 6905 6899 6587 6586 6906 6595 6907 6903 6588 6587 6598 6596 6908 6903 6591 6590 6909 6910 6911 6905 6592 6591 6740 6600 6912 6905 6595 6594 6603 6740 6913 6595 6908 6596 6914 6915 6916 6908 6599 6598 6741 6605 6917 6599 6912 6600 6742 6741 6918 6912 6913 6740 6743 6742 6919 6603 6913 6604 6744 6743 6920 6604 6917 6605 6745 6744 6921 6917 6918 6741 6746 6745 6922 6918 6919 6742 6747 6746 6923 6919 6920 6743 6748 6747 6924 6744 6920 6921 6749 6748 6925 6745 6921 6922 6750 6749 6926 6746 6922 6923 6751 6750 6927 6747 6923 6924 6752 6751 6928 6748 6924 6925 6753 6752 6929 6749 6925 6926 6754 6753 6930 6750 6926 6927 6755 6754 6931 6751 6927 6928 6756 6755 6932 6752 6928 6929 6757 6756 6933 6753 6929 6930 6325 6757 6934 6754 6930 6931 6761 6325 6935 6931 6932 6755 6762 6761 6936 6932 6933 6756 6763 6762 6937 6933 6934 6757 6482 6763 6938 6934 6935 6325 6767 6482 6939 6935 6936 6761 6768 6767 6940 6936 6937 6762 6487 6768 6941 6937 6938 6763 6772 6487 6942 6939 6482 6938 6773 6772 6770 6939 6940 6767 6628 6773 6943 6940 6941 6768 6944 6629 6945 6942 6487 6941 6777 6630 6946 6770 6772 6942 6633 6777 6775 6943 6773 6770 6781 6633 6947 6629 6628 6943 6493 6781 6779 6946 6630 6629 6948 6949 6785 6775 6777 6946 6786 6635 6950 6633 6775 6947 6636 6786 6784 6779 6781 6947 6951 6637 6783 6782 6493 6779 6952 6953 6790 6635 6782 6950 6791 6640 6954 6786 6950 6784 6641 6791 6789 6637 6636 6784 6955 6642 6788 6787 6638 6637 6956 6792 6955 6640 6787 6954 6957 6958 6959 6791 6954 6789 6958 6960 6961 6641 6789 6642 6960 6962 6798 6500 6642 6792 6647 6646 6963 6502 6792 6793 6648 6647 6797 6644 6793 6794 6803 6648 6800 6645 6794 6795 6649 6803 6802 6646 6795 6963 6964 6650 6801 6647 6963 6797 6965 6652 6964 6648 6797 6800 6966 6804 6965 6803 6800 6802 6967 6805 6966 6649 6802 6650 6968 6969 6970 6651 6650 6652 6969 6971 6810 6510 6652 6804 6811 6656 6972 6512 6804 6805 6657 6811 6809 6806 6654 6805 6973 6658 6808 6807 6655 6806 6974 6812 6973 6656 6807 6972 6975 6976 6816 6811 6972 6809 6817 6661 6977 6657 6809 6658 6521 6817 6815 6812 6517 6658 6978 6979 6821 6813 6660 6812 6822 6663 6980 6661 6813 6977 6665 6822 6820 6815 6817 6977 6981 6982 6983 6818 6521 6815 6526 6824 6984 6980 6663 6818 6985 6986 6987 6820 6822 6980 6529 6826 6988 6820 6823 6665 6989 6990 6991 6984 6824 6823 6829 6828 6992 6984 6825 6526 6667 6829 6993 6825 6988 6826 6994 6995 6996 6827 6529 6988 6830 6669 6997 6827 6992 6828 6677 6830 6998 6992 6993 6829 6678 6677 6832 6993 6668 6667 6831 6678 200 6668 6997 6669 202 6831 199 6997 6998 6830 6833 202 6999 6677 6998 6832 193 6680 197 6834 193 6675 202 6833 191 199 6831 200 6835 6675 6837 6999 202 199 6838 6840 6836 6833 197 6680 6838 7000 7001 6537 6836 6682 6536 6835 6537 6835 6834 6675 6839 7002 7003 6839 6540 6681 6682 6836 6840 6839 6840 7002 6683 6540 6839 6541 6684 6685 6405 6404 6841 7004 7005 7006 6685 6842 6686 6404 7007 6842 7008 7009 7010 7007 6545 6843 739 736 7011 6545 6544 6843 6546 7012 6844 735 734 6544 7012 7013 6845 729 734 733 7013 6692 6846 6844 729 6546 7014 7015 7016 6844 7012 6845 6690 7017 6847 6845 7013 6846 7017 6697 6848 6846 6692 6691 7018 7019 7020 6691 6690 6847 6695 7021 6849 6847 7017 6848 7021 7022 6700 6697 6696 6848 7022 6852 6853 6696 6695 6849 6852 7023 6702 7021 6700 6849 7023 6856 6857 6700 7022 6853 6856 7024 6704 6852 6702 6853 7024 6860 6861 6702 7023 6857 7025 7026 6863 6856 6704 6857 6862 7027 6706 7024 6861 6704 7027 6865 6866 6860 6553 6861 7028 7029 6868 6862 6706 6553 6867 7030 6708 7027 6866 6706 7030 6870 6709 6557 6866 6865 6870 6712 6872 6867 6708 6557 7031 6710 6871 7030 6709 6708 7032 7033 7034 6870 6872 6709 7033 7035 6875 6711 6872 6712 6874 7036 6715 6562 6711 6710 7036 6877 6716 6714 6562 6873 6877 6879 6717 6715 6714 6874 6879 6720 6881 7036 6716 6715 7037 6718 6880 6877 6717 6716 7038 6721 7037 6879 6881 6717 7039 6882 7038 6719 6881 6720 7040 7041 7042 6722 6719 6718 7041 7043 7044 6569 6722 6721 7043 7045 6886 6571 6569 6882 6885 7046 6725 6573 6571 6883 7046 6888 6726 6724 6573 6884 6888 6729 6890 6885 6725 6724 7047 6727 6889 7046 6726 6725 7048 6730 7047 6888 6890 6726 7049 7050 6892 6728 6890 6729 6891 7051 6733 6731 6728 6727 7051 6736 6894 6730 6579 6731 7052 6734 6893 6891 6733 6579 7053 7054 6898 7051 6894 6733 6895 7055 6738 6735 6894 6736 7055 6897 6899 6734 6583 6735 6897 7056 6587 6895 6738 6583 7056 6902 6903 6738 7055 6899 7057 7058 7059 6897 6587 6899 6904 6907 6905 6587 7056 6903 7060 7061 7062 6902 6591 6903 6906 7063 6908 6591 6904 6905 7063 7064 6599 6907 6595 6905 7064 6911 6912 6595 6906 6908 6911 7065 6913 6908 7063 6599 7065 7066 6604 6599 7064 6912 7066 7067 6917 6912 6911 6913 7067 7068 6918 6913 7065 6604 7068 7069 6919 6917 6604 7066 7069 7070 6920 6918 6917 7067 7070 7071 6921 6918 7068 6919 7071 7072 6922 6919 7069 6920 7072 6461 6923 6920 7070 6921 6461 7073 6924 6922 6921 7071 7073 7074 6925 6923 6922 7072 7074 7075 6926 6924 6923 6461 7075 7076 6927 6925 6924 7073 7076 7077 6928 6926 6925 7074 7077 7078 6929 6927 6926 7075 7078 7079 6930 6928 6927 7076 7079 7080 6931 6929 6928 7077 7080 7081 6932 6930 6929 7078 7081 7082 6933 6931 6930 7079 7082 7083 6934 6932 6931 7080 7083 7084 6935 6933 6932 7081 7084 7085 6936 6933 7082 6934 7085 7086 6937 6934 7083 6935 7086 7087 6938 6935 7084 6936 7087 7088 6939 6937 6936 7085 7088 7089 6940 6937 7086 6938 7089 6766 6941 6938 7087 6939 6766 6771 6942 6939 7088 6940 7090 7091 7092 6940 7089 6941 6769 6945 6943 6941 6766 6942 7093 7094 7095 6771 6770 6942 6944 6776 6946 6770 6769 6943 7096 7097 7098 6945 6629 6943 6774 6780 6947 6629 6944 6946 7099 6778 7098 6776 6775 6946 6778 7100 6782 6774 6947 6775 7100 6785 6950 6780 6779 6947 7101 6783 6949 6778 6782 6779 7102 7103 6952 7100 6950 6782 6951 7104 6787 6784 6950 6785 7104 6790 6954 6783 6637 6784 7105 6788 6953 6951 6787 6637 7106 7107 7108 7104 6954 6787 7107 7109 6957 6789 6954 6790 6956 7110 6793 6642 6789 6788 7110 6959 6794 6792 6642 6955 6959 6961 6795 6793 6792 6956 6961 6798 6963 7110 6794 6793 7111 6796 6962 6959 6795 6794 7112 6799 7111 6961 6963 6795 7113 6801 7112 6797 6963 6798 7114 6964 7113 6800 6797 6796 7115 7116 7117 6802 6800 6799 7116 7118 7119 6650 6802 6801 7118 7120 6968 6652 6650 6964 6967 7121 6806 6804 6652 6965 7121 6970 6807 6805 6804 6966 6970 6810 6972 6967 6806 6805 7122 6808 6971 7121 6807 6806 7123 7124 7125 6970 6972 6807 7124 7126 6975 6809 6972 6810 6974 7127 6813 6658 6809 6808 7127 6816 6977 6973 6812 6658 7128 7129 6978 6974 6813 6812 6814 7130 6818 7127 6977 6813 7130 6821 6980 6816 6815 6977 7131 7132 6981 6814 6818 6815 6819 7133 6823 7130 6980 6818 7133 6983 6984 6821 6820 6980 6983 7134 6825 6819 6823 6820 7134 6987 6988 6823 7133 6984 6987 7135 6827 6983 6825 6984 7135 7136 6992 6825 7134 6988 7136 7137 6993 6988 6987 6827 7137 7138 6668 6827 7135 6992 7138 6996 6997 6992 7136 6993 6996 7139 6998 6993 7137 6668 7139 6672 6832 6997 6668 7138 7140 7141 7142 6997 6996 6998 198 7143 199 6998 7139 6832 7143 196 6999 200 6832 6672 7144 7145 7146 6676 7000 6837 6999 197 6833 6999 199 7143 195 206 6676 197 6999 196 7002 6838 7001 197 194 193 193 195 6675 7001 7147 7148 6835 6837 6836 6837 6675 6676 6841 7003 7149 7003 6683 6839 6840 6838 7002 7003 7002 7150 6841 6683 7003 6684 6404 6842 6253 6252 6405 6251 7151 6252 6842 7007 6843 6252 7152 7007 7153 761 735 7153 6545 7152 740 7154 6546 7153 735 6545 7155 7012 7154 735 761 733 7156 7013 7155 6546 733 740 7157 6692 7156 7012 6546 7154 7158 6690 7157 7012 7155 7013 7159 7017 7158 7013 7156 6692 7160 6697 7159 6692 7157 6690 7161 6695 7160 6690 7158 7017 7162 7021 7161 7017 7159 6697 6850 7022 7162 6697 7160 6695 7163 7164 7165 6695 7161 7021 6854 7023 6851 7021 7162 7022 7166 7167 7168 7022 6850 6852 6858 7024 6855 6852 6851 7023 7169 6859 7168 7023 6854 6856 7170 6862 6859 6855 7024 6856 6863 7027 7170 7024 6858 6860 7171 7172 7028 6859 6862 6860 7173 6867 6864 7170 7027 6862 6868 7030 7173 7027 6863 6865 7174 6869 7029 6864 6867 6865 7175 7176 7177 7173 7030 6867 7178 7032 7176 6868 6870 7030 7179 6873 7031 6869 6712 6870 7034 6874 7179 6710 6712 6871 6875 7036 7034 7031 6873 6710 7180 6876 7035 7179 6874 6873 7181 6878 7180 7034 7036 6874 7182 6880 7181 6875 6877 7036 7183 7184 7185 6876 6879 6877 7186 7187 7183 6878 6720 6879 7188 7040 7186 6718 6720 6880 7189 6883 7039 6721 6718 7037 7042 6884 7189 6882 6721 7038 7044 6885 7042 6883 6882 7039 6886 7046 7044 7189 6884 6883 7190 6887 7045 7042 6885 6884 7191 6889 7190 7044 7046 6885 7192 7193 7194 6886 6888 7046 7195 7049 7192 6887 6729 6888 7196 6891 7048 6889 6727 6729 6892 7051 7196 7047 6730 6727 7197 6893 7050 7048 6891 6730 7198 7053 7199 7196 7051 6891 7200 6895 7052 6892 6736 7051 6898 7055 7200 6893 6734 6736 7201 7202 7203 7052 6895 6734 6900 7056 6896 6895 7200 7055 7204 6901 7203 7055 6898 6897 7205 6904 6901 6896 7056 6897 7059 6907 7205 7056 6900 6902 7206 6906 7059 6901 6904 6902 7062 7063 7206 6904 7205 6907 6909 7064 7062 6907 7059 6906 7207 7208 7209 6906 7206 7063 7210 7065 6910 7063 7062 7064 7211 7066 7210 6911 7064 6909 7211 7212 7067 6911 6910 7065 6914 7068 7212 7065 7210 7066 7213 7069 6914 7067 7066 7211 7214 7070 7213 7068 7067 7212 7215 7071 7214 7069 7068 6914 7215 6462 7072 7069 7213 7070 7216 7217 7218 7071 7070 7214 7219 7073 6460 7072 7071 7215 7217 7074 7219 6461 7072 6462 7220 7075 7217 7073 6461 6460 7221 7076 7220 7074 7073 7219 7222 7077 7221 7075 7074 7217 7223 7078 7222 7076 7075 7220 7224 7079 7223 7077 7076 7221 7225 7080 7224 7078 7077 7222 7226 7081 7225 7079 7078 7223 7227 7082 7226 7080 7079 7224 7228 7083 7227 7081 7080 7225 7229 7084 7228 7082 7081 7226 7230 7085 7229 7083 7082 7227 7230 7231 7086 7083 7228 7084 7232 7087 7231 7084 7229 7085 7233 7088 7232 7086 7085 7230 6764 7089 7233 7087 7086 7231 7234 7235 7236 7087 7232 7088 7237 6771 6765 7088 7233 7089 7238 6769 7237 7089 6764 6766 7092 6945 7238 6766 6765 6771 7239 6944 7092 7237 6769 6771 7095 6776 7239 6769 7238 6945 7240 6774 7095 7092 6944 6945 7098 6780 7240 6944 7239 6776 7241 7242 7243 7095 6774 6776 6948 7100 7099 6774 7240 6780 7244 6949 7242 7098 6778 6780 7245 7102 7246 7099 7100 6778 7247 6951 7101 6948 6785 7100 6952 7104 7247 6949 6783 6785 7248 6953 7103 7101 6951 6783 7249 7106 7250 7247 7104 6951 7251 6955 7105 6952 6790 7104 7108 6956 7251 6788 6790 6953 6957 7110 7108 7105 6955 6788 7252 6958 7109 7251 6956 6955 7253 6960 7252 7108 7110 6956 7254 6962 7253 6957 6959 7110 7255 7256 7257 6958 6961 6959 7258 7259 7255 6960 6798 6961 7260 7261 7258 6796 6798 6962 7262 7115 7260 6799 6796 7111 7263 6965 7114 6801 6799 7112 7117 6966 7263 6964 6801 7113 7119 6967 7117 6965 6964 7114 6968 7121 7119 7263 6966 6965 7264 6969 7120 7117 6967 6966 7265 6971 7264 7119 7121 6967 7266 7123 7267 6968 6970 7121 7268 6973 7122 6969 6810 6970 7125 6974 7268 6808 6810 6971 6975 7127 7125 7122 6973 6808 7269 7270 7128 7268 6974 6973 7271 6814 6976 7125 7127 6974 6978 7130 7271 7127 6975 6816 7272 6979 7129 6976 6814 6816 7273 6819 6979 7271 7130 6814 6981 7133 7273 7130 6978 6821 7274 7275 7276 6979 6819 6821 6985 7134 6982 6819 7273 7133 7277 7278 7279 7133 6981 6983 7280 7135 6986 6983 6982 7134 7280 7281 7136 7134 6985 6987 6991 7137 7281 6987 6986 7135 6994 7138 6991 7136 7135 7280 7282 7283 7284 7136 7281 7137 7285 7139 6995 7137 6991 7138 7286 6672 7285 6996 7138 6994 7286 7287 198 6996 6995 7139 7288 7143 7287 7139 7285 6672 7289 196 7288 198 6672 7286 207 194 7289 198 7287 7143 7145 6676 206 7143 7288 196 7147 7000 7145 196 7289 194 7145 206 7146 207 195 194 7001 7148 7150 7148 211 7290 6837 7000 6838 7000 6676 7145 6405 7149 7291 7003 7150 7149 7002 7001 7150 7149 7150 7292 6841 7149 6405 6252 7007 6404 7293 7151 6251 7293 7009 7151 7007 7152 6545 7151 7294 7152 761 7295 737 7153 7294 7295 739 7296 7154 761 7153 7295 7296 7297 7155 740 761 737 7298 7156 7297 7154 740 739 7299 7157 7298 7155 7154 7296 7300 7158 7299 7156 7155 7297 7300 7301 7159 7156 7298 7157 7014 7160 7301 7157 7299 7158 7302 7161 7014 7159 7158 7300 7302 7303 7162 7159 7301 7160 7018 6850 7303 7160 7014 7161 7018 7304 6851 7161 7302 7162 7165 6854 7304 7162 7303 6850 7165 7305 6855 6850 7018 6851 7168 6858 7305 6851 7304 6854 7306 7307 7308 6854 7165 6855 7025 7170 7169 6855 7305 6858 7309 7026 7308 6858 7168 6859 7026 7310 6864 7169 7170 6859 7028 7173 7310 7170 7025 6863 7311 7029 7172 6863 7026 6864 7175 7312 7313 7310 7173 6864 7174 7314 6871 7028 6868 7173 7177 7031 7314 7029 6869 6868 7032 7179 7177 6869 7174 6871 7315 7033 7178 7314 7031 6871 7316 7035 7315 7177 7179 7031 7317 7318 7319 7032 7034 7179 7320 7319 7321 7033 6875 7034 7321 7322 7185 7035 6876 6875 7323 7037 7182 7180 6878 6876 7184 7038 7323 7181 6880 6878 7187 7039 7184 7037 6880 7182 7040 7189 7187 7323 7038 7037 7324 7041 7188 7184 7039 7038 7325 7043 7324 7187 7189 7039 7326 7045 7325 7040 7042 7189 7327 7328 7329 7041 7044 7042 7194 7329 7330 7043 6886 7044 7191 7331 7047 7045 6887 6886 7193 7048 7331 7190 6889 6887 7049 7196 7193 6889 7191 7047 7332 7050 7195 7331 7048 7047 7333 7334 7199 7193 7196 7048 7335 7052 7197 7049 6892 7196 7053 7200 7335 6892 7050 6893 7201 7336 7337 7197 7052 6893 7054 7338 6896 7335 7200 7052 7203 6900 7338 7200 7053 6898 7339 7340 7341 6898 7054 6896 7057 7205 7204 6896 7338 6900 7342 7343 7344 6900 7203 6901 7060 7206 7058 6901 7204 7205 7345 7346 7347 7205 7057 7059 7348 6909 7061 7059 7058 7206 7348 7349 6910 7206 7060 7062 7350 7210 7349 7062 7061 6909 7351 7211 7350 6910 6909 7348 7351 6915 7212 7210 6910 7349 7352 7353 7354 7210 7350 7211 7355 7213 6916 7212 7211 7351 7356 7214 7355 6914 7212 6915 7356 7357 7215 7213 6914 6916 7357 7358 6462 7214 7213 7355 7358 7359 6460 7356 7215 7214 7359 7218 7219 6462 7215 7357 7220 7216 7360 6460 6462 7358 7221 7360 7361 7219 6460 7359 7222 7361 7362 7217 7219 7218 7223 7362 7363 7220 7217 7216 7224 7363 7364 7221 7220 7360 7225 7364 7365 7222 7221 7361 7226 7365 7366 7223 7222 7362 7367 7368 7369 7224 7223 7363 7370 7227 7366 7225 7224 7364 7371 7228 7370 7226 7225 7365 7372 7229 7371 7227 7226 7366 7373 7230 7372 7228 7227 7370 7373 7374 7231 7229 7228 7371 7374 7375 7232 7229 7372 7230 6759 7233 7375 7231 7230 7373 7376 6764 6759 7232 7231 7374 7376 7377 6765 7232 7375 7233 7236 7237 7377 7233 6759 6764 7090 7238 7236 6765 6764 7376 7378 7379 7380 6765 7377 7237 7093 7239 7091 7237 7236 7238 7381 7382 7383 7238 7090 7092 7096 7240 7094 7092 7091 7239 7243 7384 7385 7239 7093 7095 7386 7099 7097 7094 7240 7095 7242 6948 7386 7240 7096 7098 7387 7388 7246 7098 7097 7099 7389 7101 7244 7386 6948 7099 7102 7247 7389 6948 7242 6949 7390 7103 7245 7244 7101 6949 7391 7392 7250 7389 7247 7101 7393 7105 7248 7102 6952 7247 7106 7251 7393 6952 7103 6953 7394 7107 7249 7248 7105 6953 7395 7109 7394 7393 7251 7105 7396 7397 7398 7106 7108 7251 7399 7398 7400 7107 6957 7108 7257 7400 7401 7109 6958 6957 7402 7111 7254 7252 6960 6958 7256 7112 7402 7253 6962 6960 7259 7113 7256 7254 7111 6962 7261 7114 7259 7112 7111 7402 7115 7263 7261 7256 7113 7112 7403 7116 7262 7259 7114 7113 7404 7118 7403 7261 7263 7114 7405 7120 7404 7115 7117 7263 7406 7407 7408 7116 7119 7117 7408 7409 7267 7118 6968 7119 7410 7122 7265 7120 6969 6968 7123 7268 7410 6969 7264 6971 7411 7124 7266 7265 7122 6971 7269 7412 7413 7410 7268 7122 7126 7414 6976 7123 7125 7268 7128 7271 7414 7125 7124 6975 7415 7129 7270 6975 7126 6976 7416 7417 7418 7414 7271 6976 7131 7273 7272 7271 7128 6978 7419 7132 7418 6978 7129 6979 7132 7420 6982 7272 7273 6979 7276 6985 7420 7273 7131 6981 7276 7421 6986 6981 7132 6982 7279 7280 7421 6982 7420 6985 7279 6989 7281 6986 6985 7276 7422 7423 7424 6986 7421 7280 7425 6994 6990 7281 7280 7279 7425 7426 6995 7281 6989 6991 7427 7285 7426 6991 6990 6994 7428 7286 7427 6995 6994 7425 7428 7429 7287 7285 6995 7426 7429 7430 7288 7285 7427 7286 7431 7289 7430 7287 7286 7428 7142 207 7431 7288 7287 7429 206 7142 7146 7288 7430 7289 211 7147 7144 7431 207 7289 7146 204 7144 7142 206 207 7290 210 7432 7433 7291 7434 7000 7147 7001 7147 7145 7144 6251 6253 7291 7149 7292 7291 7150 7148 7292 7292 7434 7291 6405 7291 6253 6252 7151 7152 7010 7009 7293 756 755 759 7152 7294 7153 7009 7435 7294 742 7436 7437 738 7295 7435 7011 7438 7296 737 7295 738 7438 7439 7297 736 739 737 7439 7440 7298 7296 739 7011 7441 7299 7440 7297 7296 7438 7442 7300 7441 7298 7297 7439 7442 7015 7301 7299 7298 7440 7443 7444 7445 7299 7441 7300 7446 7302 7016 7301 7300 7442 7446 7019 7303 7014 7301 7015 7447 7448 7449 7014 7016 7302 7020 7163 7304 7303 7302 7446 7450 7451 7452 7303 7019 7018 7164 7166 7305 7304 7018 7020 7306 7453 7454 7304 7163 7165 7167 7455 7169 7165 7164 7305 7308 7025 7455 7305 7166 7168 7456 7457 7458 7168 7167 7169 7309 7171 7310 7169 7455 7025 7459 7172 7456 7025 7308 7026 7312 7460 7461 7026 7309 7310 7311 7462 7174 7171 7028 7310 7462 7175 7314 7028 7172 7029 7463 7176 7313 7029 7311 7174 7464 7178 7463 7174 7462 7314 7465 7466 7467 7175 7177 7314 7318 7467 7468 7176 7032 7177 7316 7469 7180 7178 7033 7032 7469 7317 7181 7315 7035 7033 7317 7320 7182 7316 7180 7035 7185 7323 7320 7180 7469 7181 7470 7183 7322 7181 7317 7182 7471 7186 7470 7320 7323 7182 7472 7188 7471 7185 7184 7323 7473 7474 7475 7183 7187 7184 7476 7475 7477 7186 7040 7187 7328 7477 7478 7188 7041 7040 7326 7479 7190 7324 7043 7041 7479 7327 7191 7325 7045 7043 7327 7194 7331 7045 7326 7190 7480 7192 7330 7190 7479 7191 7481 7195 7480 7191 7327 7331 7333 7482 7483 7194 7193 7331 7332 7484 7197 7192 7049 7193 7199 7335 7484 7049 7195 7050 7485 7198 7334 7050 7332 7197 7198 7486 7054 7484 7335 7197 7486 7201 7338 7335 7199 7053 7339 7487 7488 7053 7198 7054 7202 7489 7204 7054 7486 7338 7341 7057 7489 7338 7201 7203 7341 7490 7058 7203 7202 7204 7344 7060 7490 7204 7489 7057 7344 7491 7061 7057 7341 7058 7347 7348 7491 7058 7490 7060 7347 7492 7349 7061 7060 7344 7492 7493 7350 7061 7491 7348 7207 7351 7493 7349 7348 7347 7207 7494 6915 7350 7349 7492 7494 7495 6916 7350 7493 7351 7496 7355 7495 6915 7351 7207 7497 7356 7496 6916 6915 7494 7497 7498 7357 7355 6916 7495 7498 7499 7358 7356 7355 7496 7499 7500 7359 7497 7357 7356 7500 7501 7218 7498 7358 7357 7501 7502 7216 7499 7359 7358 7502 7503 7360 7500 7218 7359 7503 7504 7361 7501 7216 7218 7504 7505 7362 7502 7360 7216 7505 7506 7363 7503 7361 7360 7506 7507 7364 7504 7362 7361 7507 7508 7365 7505 7363 7362 7508 7509 7366 7506 7364 7363 7509 7510 7370 7365 7364 7507 7511 7371 7510 7366 7365 7508 7369 7372 7511 7370 7366 7509 7512 7373 7369 7371 7370 7510 7512 7513 7374 7372 7371 7511 7513 6760 7375 7373 7372 7369 7514 7515 7516 7374 7373 7512 7517 7376 6758 7375 7374 7513 7517 7234 7377 6759 7375 6760 7518 7519 7520 6759 6758 7376 7521 7090 7235 7377 7376 7517 7521 7522 7091 7377 7234 7236 7380 7093 7522 7236 7235 7090 7380 7523 7094 7090 7521 7091 7383 7096 7523 7091 7522 7093 7383 7524 7097 7093 7380 7094 7524 7243 7386 7094 7523 7096 7387 7525 7526 7096 7383 7097 7241 7527 7244 7097 7524 7386 7246 7389 7527 7386 7243 7242 7528 7245 7388 7242 7241 7244 7391 7529 7530 7527 7389 7244 7390 7531 7248 7246 7102 7389 7250 7393 7531 7102 7245 7103 7532 7249 7392 7103 7390 7248 7533 7534 7535 7531 7393 7248 7397 7535 7536 7250 7106 7393 7395 7537 7252 7249 7107 7106 7537 7396 7253 7394 7109 7107 7396 7399 7254 7395 7252 7109 7399 7257 7402 7252 7537 7253 7538 7255 7401 7253 7396 7254 7539 7258 7538 7254 7399 7402 7540 7260 7539 7257 7256 7402 7541 7262 7540 7255 7259 7256 7542 7543 7544 7258 7261 7259 7545 7544 7546 7260 7115 7261 7407 7546 7547 7262 7116 7115 7405 7548 7264 7403 7118 7116 7548 7406 7265 7404 7120 7118 7267 7410 7406 7120 7405 7264 7549 7266 7409 7264 7548 7265 7412 7550 7551 7406 7410 7265 7411 7552 7126 7267 7123 7410 7552 7269 7414 7123 7266 7124 7553 7270 7413 7124 7411 7126 7416 7554 7555 7126 7552 7414 7415 7556 7272 7269 7128 7414 7418 7131 7556 7128 7270 7129 7557 7558 7559 7129 7415 7272 7419 7274 7420 7272 7556 7131 7560 7561 7562 7131 7418 7132 7275 7277 7421 7420 7132 7419 7563 7564 7565 7420 7274 7276 7278 7566 6989 7421 7276 7275 7566 7567 6990 7421 7277 7279 7424 7425 7567 6989 7279 7278 7424 7568 7426 6990 6989 7566 7568 7569 7427 6990 7567 7425 7282 7428 7569 7426 7425 7424 7282 7570 7429 7427 7426 7568 7570 7571 7430 7428 7427 7569 7571 7140 7431 7429 7428 7282 220 213 209 7430 7429 7570 204 7146 7141 7431 7430 7571 203 7144 204 7431 7140 7142 7432 7434 7290 7141 7146 7142 209 7572 7432 7148 7290 7292 7147 211 7148 211 7144 203 7433 7573 7574 7433 6251 7291 7292 7290 7434 7433 7434 7573 7293 6251 7433 7151 7009 7294 7004 7008 7010 7006 7008 7004 7294 7435 7295 7575 7435 7008 743 7576 7011 744 738 7575 7576 7577 7438 736 738 744 7577 7578 7439 743 7011 736 7578 7579 7440 7576 7438 7011 7579 7580 7441 7439 7438 7577 730 7442 7580 7440 7439 7578 730 7581 7015 7441 7440 7579 7581 7582 7016 7441 7580 7442 7583 7446 7582 7015 7442 730 7583 7584 7019 7016 7015 7581 7584 7585 7020 7016 7582 7446 7585 7447 7163 7019 7446 7583 7447 7586 7164 7019 7584 7020 7586 7450 7166 7163 7020 7585 7450 7587 7167 7163 7447 7164 7587 7306 7455 7166 7164 7586 7588 7457 7589 7166 7450 7167 7307 7590 7309 7167 7587 7455 7590 7456 7171 7455 7306 7308 7591 7460 7592 7308 7307 7309 7459 7593 7311 7309 7590 7171 7593 7312 7462 7171 7456 7172 7461 7594 7313 7172 7459 7311 7595 7596 7597 7311 7593 7462 7598 7466 7596 7462 7312 7175 7464 7599 7315 7313 7176 7175 7599 7465 7316 7463 7178 7176 7465 7318 7469 7178 7464 7315 7468 7600 7319 7315 7599 7316 7600 7601 7321 7316 7465 7469 7601 7602 7322 7469 7318 7317 7603 7604 7605 7317 7319 7320 7606 7607 7604 7320 7321 7185 7608 7474 7607 7322 7183 7185 7472 7609 7324 7470 7186 7183 7609 7473 7325 7471 7188 7186 7473 7476 7326 7472 7324 7188 7476 7328 7479 7324 7609 7325 7478 7610 7329 7325 7473 7326 7610 7611 7330 7326 7476 7479 7612 7613 7614 7479 7328 7327 7615 7482 7613 7327 7329 7194 7481 7616 7332 7330 7192 7194 7616 7333 7484 7192 7480 7195 7483 7617 7334 7195 7481 7332 7618 7619 7620 7332 7616 7484 7485 7336 7486 7199 7484 7333 7619 7621 7337 7199 7334 7198 7337 7622 7202 7198 7485 7486 7622 7339 7489 7201 7486 7336 7623 7624 7625 7201 7337 7202 7340 7342 7490 7489 7202 7622 7626 7627 7628 7489 7339 7341 7343 7345 7491 7490 7341 7340 7629 7630 7631 7490 7342 7344 7346 7632 7492 7491 7344 7343 7632 7208 7493 7347 7491 7345 7633 7634 7635 7492 7347 7346 7209 7636 7494 7493 7492 7632 7636 7637 7495 7207 7493 7208 7637 7638 7496 7494 7207 7209 7639 7497 7638 7495 7494 7636 7639 7640 7498 7496 7495 7637 7640 7641 7499 7497 7496 7638 7641 7642 7500 7639 7498 7497 7642 7643 7501 7640 7499 7498 7643 7644 7502 7641 7500 7499 7644 7645 7503 7642 7501 7500 7645 7646 7504 7643 7502 7501 7646 7647 7505 7644 7503 7502 7647 7648 7506 7645 7504 7503 7648 7649 7507 7646 7505 7504 7649 7650 7508 7647 7506 7505 7650 7651 7509 7648 7507 7506 7651 7652 7510 7649 7508 7507 7652 7367 7511 7509 7508 7650 7653 7654 7655 7510 7509 7651 7656 7512 7368 7511 7510 7652 7656 7657 7513 7369 7511 7367 7657 7658 6760 7512 7369 7368 7658 7659 6758 7513 7512 7656 7660 7517 7659 6760 7513 7657 7660 7661 7234 6758 6760 7658 7661 7662 7235 6758 7659 7517 7520 7521 7662 7234 7517 7660 7520 7378 7522 7235 7234 7661 7663 7664 7665 7235 7662 7521 7379 7381 7523 7522 7521 7520 7666 7667 7668 7522 7378 7380 7382 7384 7524 7523 7380 7379 7667 7669 7385 7523 7381 7383 7385 7670 7241 7383 7382 7524 7670 7387 7527 7243 7524 7384 7671 7388 7526 7243 7385 7241 7672 7529 7673 7241 7670 7527 7528 7674 7390 7387 7246 7527 7674 7391 7531 7246 7388 7245 7530 7675 7392 7245 7528 7390 7676 7534 7677 7390 7674 7531 7532 7678 7394 7531 7391 7250 7678 7533 7395 7392 7249 7250 7533 7397 7537 7249 7532 7394 7536 7679 7398 7394 7678 7395 7679 7680 7400 7395 7533 7537 7680 7681 7401 7537 7397 7396 7682 7683 7684 7396 7398 7399 7685 7686 7683 7399 7400 7257 7687 7688 7686 7401 7255 7257 7689 7543 7688 7538 7258 7255 7541 7690 7403 7539 7260 7258 7690 7542 7404 7540 7262 7260 7542 7545 7405 7541 7403 7262 7545 7407 7548 7403 7690 7404 7547 7691 7408 7404 7542 7405 7692 7409 7691 7405 7545 7548 7693 7550 7694 7548 7407 7406 7549 7695 7411 7408 7267 7406 7695 7412 7552 7267 7409 7266 7551 7696 7413 7266 7549 7411 7697 7554 7698 7411 7695 7552 7553 7699 7415 7552 7412 7269 7699 7416 7556 7269 7413 7270 7700 7558 7701 7270 7553 7415 7417 7702 7419 7415 7699 7556 7702 7557 7274 7556 7416 7418 7557 7703 7275 7418 7417 7419 7703 7560 7277 7274 7419 7702 7560 7704 7278 7274 7557 7275 7704 7563 7566 7277 7275 7703 7563 7422 7567 7278 7277 7560 7705 7706 7707 7566 7278 7704 7423 7708 7568 7567 7566 7563 7708 7283 7569 7424 7567 7422 7709 7710 7711 7568 7424 7423 7284 7712 7570 7569 7568 7708 7712 7713 7571 7282 7569 7283 7713 7714 7140 7284 7570 7282 7714 7715 7141 7712 7571 7570 7715 205 204 7140 7571 7713 203 205 208 7141 7140 7714 208 205 7716 7141 7715 204 7432 7572 7573 7572 213 212 211 210 7290 210 203 208 7010 7574 7717 7574 7293 7433 7434 7432 7573 7574 7573 7718 7010 7293 7574 7008 7435 7009 7719 7006 7005 7719 747 7006 7435 7575 738 7720 7575 7006 742 7437 7576 741 744 7720 7437 7721 7577 741 743 744 7721 7722 7578 742 7576 743 7722 7723 7579 7437 7577 7576 7723 731 7580 7721 7578 7577 732 7724 7725 7579 7578 7722 732 7725 7581 7580 7579 7723 7725 7726 7582 731 730 7580 7726 7727 7583 7581 730 732 7727 7728 7584 7582 7581 7725 7728 7448 7585 7583 7582 7726 7729 7730 7731 7584 7583 7727 7449 7451 7586 7585 7584 7728 7732 7733 7734 7447 7585 7448 7452 7453 7587 7586 7447 7449 7735 7733 7588 7450 7586 7451 7454 7589 7307 7450 7452 7587 7589 7457 7590 7306 7587 7453 7736 7737 7591 7306 7454 7307 7458 7592 7459 7307 7589 7590 7592 7460 7593 7456 7590 7457 7738 7739 7740 7456 7458 7459 7740 7741 7595 7459 7592 7593 7594 7597 7463 7593 7460 7312 7597 7596 7464 7312 7461 7313 7596 7466 7599 7313 7594 7463 7467 7466 7742 7463 7597 7464 7743 7744 7745 7464 7596 7599 7745 7746 7747 7599 7466 7465 7747 7748 7749 7465 7467 7318 7749 7750 7603 7318 7468 7319 7602 7605 7470 7319 7600 7321 7605 7604 7471 7321 7601 7322 7604 7607 7472 7602 7470 7322 7607 7474 7609 7470 7605 7471 7475 7474 7751 7471 7604 7472 7477 7475 7752 7472 7607 7609 7753 7754 7755 7609 7474 7473 7755 7756 7757 7473 7475 7476 7757 7758 7612 7476 7477 7328 7611 7614 7480 7328 7478 7329 7614 7613 7481 7329 7610 7330 7613 7482 7616 7330 7611 7480 7759 7760 7761 7480 7614 7481 7762 7763 7764 7481 7613 7616 7617 7620 7485 7616 7482 7333 7620 7619 7336 7334 7333 7483 7765 7766 7767 7334 7617 7485 7621 7487 7622 7336 7485 7620 7768 7766 7623 7337 7336 7619 7488 7625 7340 7337 7621 7622 7625 7624 7342 7339 7622 7487 7624 7628 7343 7339 7488 7340 7628 7627 7345 7342 7340 7625 7627 7769 7346 7342 7624 7343 7769 7770 7632 7345 7343 7628 7770 7771 7208 7346 7345 7627 7771 7772 7209 7632 7346 7769 7772 7773 7636 7208 7632 7770 7773 7774 7637 7209 7208 7771 7774 7775 7638 7772 7636 7209 7775 7776 7639 7637 7636 7773 7776 7352 7640 7638 7637 7774 7352 7354 7641 7639 7638 7775 7354 7777 7642 7776 7640 7639 7777 7778 7643 7352 7641 7640 7778 7779 7644 7354 7642 7641 7779 7780 7645 7777 7643 7642 7780 7781 7646 7778 7644 7643 7781 7782 7647 7779 7645 7644 7782 7783 7648 7780 7646 7645 7783 7784 7649 7781 7647 7646 7784 7785 7650 7782 7648 7647 7785 7786 7651 7783 7649 7648 7786 7787 7652 7784 7650 7649 7787 7788 7367 7785 7651 7650 7788 7789 7368 7786 7652 7651 7789 7790 7656 7367 7652 7787 7790 7791 7657 7368 7367 7788 7791 7792 7658 7656 7368 7789 7792 7793 7659 7790 7657 7656 7793 7794 7660 7658 7657 7791 7794 7795 7661 7659 7658 7792 7795 7518 7662 7660 7659 7793 7796 7797 7798 7661 7660 7794 7519 7799 7378 7662 7661 7795 7799 7665 7379 7520 7662 7518 7665 7664 7381 7378 7520 7519 7664 7668 7382 7378 7799 7379 7668 7667 7384 7381 7379 7665 7800 7801 7802 7381 7664 7382 7669 7525 7670 7384 7382 7668 7803 7801 7804 7385 7384 7667 7805 7806 7807 7385 7669 7670 7671 7673 7528 7670 7525 7387 7673 7529 7674 7388 7387 7526 7808 7809 7810 7388 7671 7528 7811 7812 7813 7528 7673 7674 7675 7677 7532 7674 7529 7391 7677 7534 7678 7392 7391 7530 7535 7534 7814 7392 7675 7532 7815 7816 7817 7532 7677 7678 7817 7818 7819 7678 7534 7533 7819 7820 7821 7533 7535 7397 7821 7822 7682 7397 7536 7398 7681 7684 7538 7398 7679 7400 7684 7683 7539 7400 7680 7401 7683 7686 7540 7681 7538 7401 7686 7688 7541 7684 7539 7538 7688 7543 7690 7539 7683 7540 7544 7543 7823 7540 7686 7541 7824 7825 7826 7541 7688 7690 7826 7827 7828 7690 7543 7542 7828 7829 7830 7542 7544 7545 7831 7832 7833 7545 7546 7407 7692 7694 7549 7407 7547 7408 7694 7550 7695 7408 7691 7409 7551 7550 7834 7409 7692 7549 7835 7836 7697 7549 7694 7695 7696 7698 7553 7695 7550 7412 7698 7554 7699 7413 7412 7551 7837 7838 7700 7413 7696 7553 7555 7701 7417 7553 7698 7699 7701 7558 7702 7416 7699 7554 7839 7840 7841 7416 7555 7417 7559 7561 7703 7702 7417 7701 7842 7843 7844 7557 7702 7558 7562 7564 7704 7703 7557 7559 7845 7846 7847 7560 7703 7561 7565 7848 7422 7704 7560 7562 7848 7849 7423 7563 7704 7564 7849 7850 7708 7422 7563 7565 7850 7851 7283 7423 7422 7848 7851 7852 7284 7708 7423 7849 7852 7853 7712 7283 7708 7850 7853 7854 7713 7284 7283 7851 7854 7855 7714 7852 7712 7284 7855 7856 7715 7853 7713 7712 7856 7716 205 7854 7714 7713 7716 220 208 7715 7714 7855 7857 215 7858 7715 7856 205 212 214 215 7859 7717 216 210 209 7432 208 220 209 7004 7717 7859 7574 7718 7717 7573 7572 7718 7718 216 7717 7010 7717 7004 7008 7006 7575 745 747 7719 752 228 758 7575 7720 744 7720 747 7860 7437 7861 7721 748 741 7860 7862 7863 7864 748 7436 742 7722 7721 7865 7436 7861 7437 7723 7722 7866 7861 7865 7721 731 7723 7867 7865 7866 7722 732 731 7868 7867 7723 7866 7869 7870 7871 7868 731 7867 7726 7725 7872 7868 7724 732 7727 7726 7873 7724 7872 7725 7728 7727 7874 7873 7726 7872 7448 7728 7445 7874 7727 7873 7449 7448 7444 7445 7728 7874 7451 7449 7875 7444 7448 7445 7452 7451 7876 7875 7449 7444 7453 7452 7877 7876 7451 7875 7454 7453 7878 7877 7452 7876 7589 7454 7735 7878 7453 7877 7879 7880 7881 7735 7454 7878 7458 7457 7882 7589 7735 7588 7592 7458 7736 7882 7457 7588 7883 7884 7739 7736 7458 7882 7461 7460 7885 7592 7736 7591 7594 7461 7738 7460 7591 7885 7597 7594 7740 7738 7461 7885 7886 7887 7888 7740 7594 7738 7888 7889 7890 7597 7740 7595 7891 7892 7893 7596 7595 7598 7468 7467 7894 7466 7598 7742 7600 7468 7743 7467 7742 7894 7601 7600 7745 7468 7894 7743 7602 7601 7747 7600 7743 7745 7605 7602 7749 7747 7601 7745 7895 7896 7897 7749 7602 7747 7897 7898 7899 7605 7749 7603 7899 7900 7901 7604 7603 7606 7901 7902 7903 7607 7606 7608 7903 7904 7754 7474 7608 7751 7478 7477 7905 7475 7751 7752 7610 7478 7753 7477 7752 7905 7611 7610 7755 7478 7905 7753 7614 7611 7757 7755 7610 7753 7906 7907 7908 7757 7611 7755 7908 7909 7760 7614 7757 7612 7483 7482 7910 7613 7612 7615 7617 7483 7759 7482 7615 7910 7620 7617 7761 7759 7483 7910 7911 7912 7913 7761 7617 7759 7621 7619 7914 7620 7761 7618 7487 7621 7915 7914 7619 7618 7488 7487 7916 7915 7621 7914 7625 7488 7768 7916 7487 7915 7917 7918 7919 7768 7488 7916 7628 7624 7920 7623 7625 7768 7921 7922 7923 7920 7624 7623 7769 7627 7924 7626 7628 7920 7770 7769 7925 7924 7627 7626 7771 7770 7926 7925 7769 7924 7772 7771 7927 7925 7926 7770 7773 7772 7928 7927 7771 7926 7774 7773 7929 7928 7772 7927 7775 7774 7930 7928 7929 7773 7776 7775 7931 7929 7930 7774 7352 7776 7932 7931 7775 7930 7933 7934 7935 7932 7776 7931 7777 7354 7936 7932 7353 7352 7778 7777 7935 7353 7936 7354 7779 7778 7934 7936 7935 7777 7780 7779 7937 7935 7934 7778 7781 7780 7938 7934 7937 7779 7782 7781 7939 7937 7938 7780 7783 7782 7940 7938 7939 7781 7784 7783 7941 7939 7940 7782 7785 7784 7942 7940 7941 7783 7786 7785 7943 7941 7942 7784 7787 7786 7944 7942 7943 7785 7788 7787 7945 7943 7944 7786 7789 7788 7946 7944 7945 7787 7790 7789 7947 7945 7946 7788 7791 7790 7948 7947 7789 7946 7792 7791 7949 7948 7790 7947 7793 7792 7950 7948 7949 7791 7794 7793 7951 7949 7950 7792 7795 7794 7952 7951 7793 7950 7518 7795 7953 7952 7794 7951 7519 7518 7954 7953 7795 7952 7799 7519 7955 7954 7518 7953 7665 7799 7956 7954 7955 7519 7957 7958 7959 7956 7799 7955 7668 7664 7960 7663 7665 7956 7961 7962 7957 7960 7664 7663 7669 7667 7963 7668 7960 7666 7525 7669 7964 7963 7667 7666 7526 7525 7965 7964 7669 7963 7671 7526 7803 7525 7964 7965 7673 7671 7804 7803 7526 7965 7966 7967 7968 7804 7671 7803 7530 7529 7969 7673 7804 7672 7675 7530 7808 7529 7672 7969 7677 7675 7810 7808 7530 7969 7812 7970 7971 7810 7675 7808 7971 7972 7816 7677 7810 7676 7536 7535 7973 7534 7676 7814 7679 7536 7815 7535 7814 7973 7680 7679 7817 7536 7973 7815 7681 7680 7819 7679 7815 7817 7684 7681 7821 7819 7680 7817 7974 7975 7976 7821 7681 7819 7976 7977 7978 7684 7821 7682 7978 7979 7980 7683 7682 7685 7980 7981 7982 7686 7685 7687 7982 7983 7825 7688 7687 7689 7546 7544 7984 7543 7689 7823 7547 7546 7824 7544 7823 7984 7691 7547 7826 7546 7984 7824 7692 7691 7828 7547 7824 7826 7694 7692 7830 7828 7691 7826 7831 7985 7986 7830 7692 7828 7987 7988 7989 7694 7830 7693 7696 7551 7990 7550 7693 7834 7698 7696 7835 7990 7551 7834 7991 7992 7838 7835 7696 7990 7555 7554 7993 7698 7835 7697 7701 7555 7837 7993 7554 7697 7994 7995 7996 7837 7555 7993 7559 7558 7997 7701 7837 7700 7561 7559 7998 7997 7558 7700 7562 7561 7999 7998 7559 7997 7564 7562 8000 7999 7561 7998 7565 7564 8001 8000 7562 7999 7848 7565 8002 8001 7564 8000 7849 7848 8003 8001 8002 7565 7850 7849 8004 8003 7848 8002 7851 7850 8005 8004 7849 8003 7852 7851 8006 8004 8005 7850 7853 7852 8007 8006 7851 8005 7854 7853 8008 8007 7852 8006 7855 7854 7709 8007 8008 7853 7856 7855 7711 8008 7709 7854 7716 7856 8009 7709 7711 7855 220 7716 218 7711 8009 7856 213 220 219 8009 218 7716 7857 8010 215 7572 212 7718 209 213 7572 213 219 214 7859 8010 8011 7005 7004 7859 7718 212 216 7859 216 8010 7719 7005 7859 7006 747 7720 753 746 745 748 8012 7436 7720 7860 741 8013 7860 746 7861 7436 8014 8013 8012 748 7865 7861 8015 7436 8012 8014 7866 7865 8016 8014 8015 7861 7866 8017 7867 8015 8016 7865 7867 7863 7868 8016 8017 7866 7868 7862 7724 8017 7863 7867 7872 7724 8018 7863 7862 7868 7873 7872 8019 7862 8018 7724 7873 8020 7874 8018 8019 7872 7874 8021 7445 8019 8020 7873 8022 8023 8024 8021 7874 8020 7444 8025 7875 8021 7443 7445 7876 7875 8026 8025 7444 7443 7876 7731 7877 8025 8026 7875 7878 7877 7730 7731 7876 8026 7878 7734 7735 7731 7730 7877 8027 7881 8028 7734 7878 7730 7588 8029 7882 7733 7735 7734 7882 8030 7736 8029 7588 7733 8031 8032 8033 8030 7882 8029 7591 8034 7885 7737 7736 8030 7885 7883 7738 8034 7591 7737 8035 8036 8037 7883 7885 8034 8038 8039 8040 7739 7738 7883 7595 8041 7598 7741 7740 7739 7598 7886 7742 7595 7741 8041 7742 7888 7894 7598 8041 7886 7894 7890 7743 7888 7742 7886 7891 8042 8043 7890 7894 7888 8042 8044 8045 7744 7743 7890 8044 8046 8047 7746 7745 7744 8048 8049 8050 7748 7747 7746 7603 8051 7606 7750 7749 7748 7606 7895 7608 7603 7750 8051 7608 7897 7751 7606 8051 7895 7751 7899 7752 7608 7895 7897 7752 7901 7905 7751 7897 7899 7905 7903 7753 7901 7752 7899 8052 8053 8054 7903 7905 7901 8053 8055 8056 7754 7753 7903 8057 8058 8059 7756 7755 7754 7612 8060 7615 7758 7757 7756 7615 7906 7910 7612 7758 8060 7910 7908 7759 7906 7615 8060 8061 8062 8063 7908 7910 7906 7618 7761 8064 7760 7759 7908 7618 7764 7914 8064 7761 7760 7914 7763 7915 7764 7618 8064 7916 7915 8065 7763 7914 7764 7916 7767 7768 7763 8065 7915 8066 8067 8068 7767 7916 8065 7623 8069 7920 7766 7768 7767 7920 8070 7626 8069 7623 7766 7626 8071 7924 8070 7920 8069 7924 8072 7925 8071 7626 8070 7925 8073 7926 8071 8072 7924 7927 7926 8074 8073 7925 8072 7927 8075 7928 8073 8074 7926 7928 8076 7929 8074 8075 7927 7930 7929 8077 8076 7928 8075 7930 8078 7931 8076 8077 7929 7931 8079 7932 8077 8078 7930 7932 8080 7353 8078 8079 7931 7936 7353 8081 8079 8080 7932 7935 7936 8082 8080 8081 7353 8083 7937 7934 8081 8082 7936 8084 7938 7937 8082 7933 7935 8085 8086 8087 7933 8083 7934 7938 8088 7939 8083 8084 7937 8085 7941 7940 8084 8088 7938 8089 7942 7941 8088 8086 7939 8090 7943 7942 8086 8085 7940 8091 7944 7943 8085 8089 7941 8092 8093 8094 8089 8090 7942 7944 8095 7945 8090 8091 7943 7945 8093 7946 8091 8095 7944 7946 8092 7947 8095 8093 7945 7947 8096 7948 8093 8092 7946 7948 8097 7949 8092 8096 7947 7950 7949 8098 8097 7948 8096 7950 8099 7951 8097 8098 7949 7951 8100 7952 8098 8099 7950 7952 8101 7953 8099 8100 7951 7954 7953 8102 8101 7952 8100 7954 7515 7955 8101 8102 7953 7956 7955 7514 7515 7954 8102 7956 8103 7663 7515 7514 7955 7663 8104 7960 8103 7956 7514 7960 8105 7666 8104 7663 8103 7666 8106 7963 8105 7960 8104 7963 8107 7964 8106 7666 8105 7965 7964 8108 8107 7963 8106 7965 7802 7803 8107 8108 7964 8109 8110 8111 7802 7965 8108 7672 7804 8112 7801 7803 7802 7672 7807 7969 8112 7804 7801 7969 7806 7808 7807 7672 8112 7966 8113 8114 7806 7969 7807 7676 7810 8115 7809 7808 7806 7676 7813 7814 8115 7810 7809 7814 7812 7973 7676 8115 7813 7973 7971 7815 7812 7814 7813 8116 8117 8118 7971 7973 7812 8117 8119 8120 7816 7815 7971 8119 8121 8122 7818 7817 7816 8121 8123 8124 7820 7819 7818 7682 8125 7685 7822 7821 7820 7685 7974 7687 8125 7682 7822 7687 7976 7689 7685 8125 7974 7689 7978 7823 7687 7974 7976 7823 7980 7984 7689 7976 7978 7984 7982 7824 7980 7823 7978 8126 8127 8128 7982 7984 7980 8127 8129 8130 7825 7824 7982 8129 8131 8132 7827 7826 7825 7693 7830 8133 7829 7828 7827 7693 7832 7834 8133 7830 7829 7834 7831 7990 7693 8133 7832 7990 7986 7835 7831 7834 7832 8134 8135 8136 7986 7990 7831 7697 8137 7993 7836 7835 7986 7993 7991 7837 8137 7697 7836 8138 7996 8139 7991 7993 8137 7700 8140 7997 7838 7837 7991 7997 8141 7998 8140 7700 7838 7999 7998 8142 8141 7997 8140 7999 7841 8000 8141 8142 7998 8001 8000 7840 7841 7999 8142 8001 7844 8002 7841 7840 8000 8003 8002 7843 7844 8001 7840 8003 8143 8004 7844 7843 8002 8004 8144 8005 7843 8143 8003 8006 8005 8145 8144 8004 8143 8006 8146 8007 8144 8145 8005 8007 8147 8008 8145 8146 8006 7709 8008 8148 8147 8007 8146 8149 8150 8151 8147 8148 8008 7711 8152 8009 8148 7710 7709 8009 8150 218 7710 8152 7711 218 8149 219 8152 8150 8009 219 8153 214 8150 8149 218 214 7858 215 8153 219 8149 8154 231 7857 7858 214 8153 745 8011 8155 8011 7719 7859 216 215 8010 8011 8010 8156 745 7719 8011 747 746 7860 228 752 753 8012 750 8014 7860 8013 748 752 8157 8013 8015 8014 749 8157 750 8012 8016 8015 8158 8014 750 749 8017 8016 8159 8015 749 8158 7863 8017 8160 8158 8159 8016 8161 8162 8163 8159 8160 8017 7862 8164 8018 8160 7864 7863 8019 8018 8165 7864 8164 7862 8020 8019 8166 8018 8164 8165 8021 8020 8167 8165 8166 8019 8021 8168 7443 8166 8167 8020 8025 7443 8169 8168 8021 8167 8025 8170 8026 8168 8169 7443 7731 8026 8171 8169 8170 8025 8172 8173 8174 8170 8171 8026 7734 7730 8175 8171 7729 7731 8172 8176 8177 7729 8175 7730 8029 7733 8178 7732 7734 8175 8029 8179 8030 7732 8178 7733 7737 8030 8180 8179 8029 8178 8034 7737 7880 8180 8030 8179 8034 8181 7883 8180 7880 7737 8031 8182 8035 8181 8034 7880 7741 7739 8183 7884 7883 8181 8041 7741 8037 8183 7739 7884 8041 8184 7886 8183 8037 7741 8038 8185 8186 8184 8041 8037 8185 8187 7893 7887 7886 8184 7744 7890 8188 7889 7888 7887 7746 7744 7892 8188 7890 7889 7748 7746 8043 7892 7744 8188 7750 7748 8045 8043 7746 7892 8051 7750 8047 8045 7748 8043 8051 8189 7895 8045 8047 7750 8048 8190 8191 8189 8051 8047 8190 8192 8193 7896 7895 8189 8192 8194 8195 7898 7897 7896 8194 8196 8197 7900 7899 7898 8196 8198 8052 7902 7901 7900 7756 7754 8199 7904 7903 7902 7758 7756 8054 8199 7754 7904 8060 7758 8056 8054 7756 8199 8060 8200 7906 8054 8056 7758 8057 8201 8202 8200 8060 8056 8201 8203 8061 7907 7906 8200 8064 7760 8204 7909 7908 7907 7764 8064 8063 7909 8204 7760 8205 8206 7913 8204 8063 8064 8065 7763 8207 7762 7764 8063 7767 8065 7912 7762 8207 7763 8208 8209 8210 8207 7912 8065 8069 7766 8211 7765 7767 7912 8069 8212 8070 7765 8211 7766 8071 8070 8213 8212 8069 8211 8071 8214 8072 8212 8213 8070 8073 8072 8215 8214 8071 8213 8073 8216 8074 8214 8215 8072 8075 8074 8217 8215 8216 8073 8076 8075 8218 8216 8217 8074 8076 8219 8077 8217 8218 8075 8078 8077 8220 8218 8219 8076 8079 8078 8221 8219 8220 8077 8079 8222 8080 8220 8221 8078 8080 7635 8081 8221 8222 8079 8082 8081 8223 8222 7635 8080 7933 8082 8224 8081 7635 8223 8083 7933 8225 8082 8223 8224 8084 8083 8226 7933 8224 8225 8088 8084 8227 8083 8225 8226 8086 8088 8228 8226 8227 8084 7939 8086 7940 8088 8227 8228 8089 8085 8229 8086 8228 8087 8090 8089 8230 8085 8087 8229 8091 8090 8231 8089 8229 8230 8095 8091 8232 8090 8230 8231 8093 8095 8233 8231 8232 8091 8234 8096 8092 8232 8233 8095 8235 8236 8237 8233 8094 8093 8096 8238 8097 8094 8234 8092 8097 8239 8098 8234 8238 8096 8099 8098 8240 8238 8239 8097 8100 8099 8241 8239 8240 8098 8100 8242 8101 8240 8241 8099 8101 7653 8102 8241 8242 8100 7515 8102 8243 8242 7653 8101 8244 8245 8246 7653 8243 8102 8103 7514 8247 8243 7516 7515 8104 8103 8248 7516 8247 7514 8104 8249 8105 8247 8248 8103 8106 8105 8250 8249 8104 8248 8106 8251 8107 8249 8250 8105 8108 8107 8252 8251 8106 8250 7802 8108 7962 8251 8252 8107 8253 8254 8109 8252 7962 8108 8112 7801 8255 7800 7802 7962 7807 8112 8111 7800 8255 7801 8256 8257 7968 8255 8111 8112 7809 7806 8258 7805 7807 8111 8115 7809 7967 8258 7806 7805 7813 8115 8114 8258 7967 7809 8259 8260 8261 7967 8114 8115 8260 8262 8263 7811 7813 8114 8262 8264 8116 7970 7812 7811 7818 7816 8265 7972 7971 7970 7820 7818 8118 8265 7816 7972 7822 7820 8120 8118 7818 8265 8125 7822 8122 8120 7820 8118 7974 8125 8124 8120 8122 7822 8266 8267 8268 8122 8124 8125 8267 8269 8270 7975 7974 8124 8269 8271 8272 7977 7976 7975 8271 8273 8274 7979 7978 7977 8273 8275 8126 7981 7980 7979 7827 7825 8276 7983 7982 7981 7829 7827 8128 8276 7825 7983 8133 7829 8130 8128 7827 8276 7832 8133 8132 8128 8130 7829 8277 8278 8279 8130 8132 8133 8278 8280 7989 7833 7832 8132 7836 7986 8281 7985 7831 7833 8137 7836 7988 8281 7986 7985 8137 8282 7991 8281 7988 7836 8134 8283 8284 8282 8137 7988 8140 7838 8285 7992 7991 8282 8140 8286 8141 7992 8285 7838 8142 8141 8287 8286 8140 8285 7841 8142 7995 8286 8287 8141 8288 8289 8290 8287 7995 8142 7844 7840 8291 7995 7839 7841 8292 8293 8294 7839 8291 7840 8143 7843 8295 8291 7842 7844 8144 8143 8296 7842 8295 7843 8144 8297 8145 8295 8296 8143 8146 8145 8298 8296 8297 8144 8147 8146 8299 8297 8298 8145 8147 8300 8148 8298 8299 8146 7710 8148 8301 8299 8300 8147 8152 7710 8302 8148 8300 8301 8150 8152 8303 8301 8302 7710 8304 8305 8306 8302 8303 8152 8149 8307 8153 8303 8151 8150 8153 8306 7858 8151 8307 8149 7858 8154 7857 8307 8306 8153 7857 231 8156 8154 7858 8306 753 8155 227 8011 8156 8155 8010 7857 8156 8155 8156 8308 745 8155 753 746 752 8013 224 758 228 8309 8310 8311 8013 8157 8012 758 757 8157 8158 749 8310 757 751 750 8312 8310 8309 749 751 8310 8312 8313 8159 8159 8158 8312 8313 8314 8160 8160 8159 8313 8314 8315 7864 7864 8160 8314 8315 8316 8164 7864 8315 8164 8316 8317 8165 8164 8316 8165 8317 8318 8166 8166 8165 8317 8318 8319 8167 8167 8166 8318 8319 8320 8168 8167 8319 8168 8320 7871 8169 8168 8320 8169 7871 8321 8170 8169 7871 8170 8321 8023 8171 8170 8321 8171 8023 8322 7729 8171 8023 7729 8322 8323 8175 7729 8322 8175 8323 8324 7732 8175 8323 7732 8324 8177 8178 7732 8324 8178 8177 8325 8179 8178 8177 8179 8325 7881 8180 8179 8325 8180 8326 8033 8327 8180 7881 7880 7879 8328 8181 7880 7879 8181 8328 8032 7884 8328 7884 8181 8032 8035 8183 7884 8032 8183 8329 8040 8330 8183 8035 8037 8036 8331 8184 8037 8036 8184 8331 8039 7887 8331 7887 8184 8039 8186 7889 8039 7889 7887 8186 7893 8188 7889 8186 8188 7891 8187 8332 8188 7893 7892 8333 8334 8335 7892 7891 8043 8336 8337 8338 8043 8042 8045 8339 8050 8340 8045 8044 8047 8046 8341 8189 8047 8046 8189 8341 8049 7896 8189 8341 7896 8049 8191 7898 8049 7898 7896 8191 8193 7900 8191 7900 7898 8193 8195 7902 8193 7902 7900 8195 8197 7904 8195 7904 7902 8197 8052 8199 7904 8197 8199 8342 8343 8344 8199 8052 8054 8345 8059 8346 8054 8053 8056 8055 8347 8200 8056 8055 8200 8347 8058 7907 8347 7907 8200 8058 8202 7909 8058 7909 7907 8202 8061 8204 7909 8202 8204 8348 8205 8349 8204 8061 8063 8062 8350 7762 8063 8062 7762 8350 7913 8207 7762 8350 8207 8351 8208 8352 8207 7913 7912 7911 8353 7765 7912 7911 7765 8353 8210 8211 7765 8353 8211 8210 8354 8212 8211 8210 8212 8354 8067 8213 8212 8354 8213 8067 8355 8214 8213 8067 8214 8355 7917 8215 8214 8355 8215 7917 8356 8216 8215 7917 8216 8356 7921 8217 8216 8356 8217 7921 8357 8218 8218 8217 7921 8357 8358 8219 8218 8357 8219 8358 7629 8220 8219 8358 8220 7629 8359 8221 8221 8220 7629 8359 7633 8222 8221 8359 8222 8360 8361 8362 8222 7633 7635 7634 8361 8223 7635 7634 8223 8361 8363 8224 8224 8223 8361 8363 8364 8225 8225 8224 8363 8364 8365 8226 8226 8225 8364 8365 8366 8227 8227 8226 8365 8366 8367 8228 8228 8227 8366 8367 8368 8087 8087 8228 8367 8368 8369 8229 8229 8087 8368 8369 8370 8230 8230 8229 8369 8370 8371 8231 8231 8230 8370 8371 8372 8232 8232 8231 8371 8372 8373 8233 8233 8232 8372 8373 8374 8094 8094 8233 8373 8374 8375 8234 8234 8094 8374 8375 8376 8238 8234 8375 8238 8239 8377 8240 8238 8376 8239 8378 8377 8237 8239 8376 8377 8378 8379 8241 8241 8240 8378 8379 7654 8242 8241 8379 8242 8380 8381 8382 8242 7654 7653 7655 8381 8243 7653 7655 8243 8381 8383 7516 8243 8381 7516 8383 8384 8247 7516 8383 8247 8384 8385 8248 8248 8247 8384 8385 8386 8249 8248 8385 8249 8386 7798 8250 8249 8386 8250 7798 8387 8251 8250 7798 8251 8387 7957 8252 8251 8387 8252 8388 8253 8389 8252 7957 7962 7961 8390 7800 7962 7961 7800 8390 8109 8255 7800 8390 8255 8391 8256 8392 8255 8109 8111 8110 8393 7805 8111 8110 7805 8393 7968 8258 7805 8393 8258 8394 8395 8396 8258 7968 7967 8397 8259 8398 7967 7966 8114 8113 8399 7811 8114 8113 7811 8399 8261 7970 8399 7970 7811 8261 8263 7972 8261 7972 7970 8263 8116 8265 7972 8263 8265 8400 8401 8402 8265 8116 8118 8403 8404 8405 8118 8117 8120 8406 8407 8408 8120 8119 8122 8409 8266 8410 8122 8121 8124 8123 8411 7975 8124 8123 7975 8411 8268 7977 8411 7977 7975 8268 8270 7979 8268 7979 7977 8270 8272 7981 8270 7981 7979 8272 8274 7983 8272 7983 7981 8274 8126 8276 7983 8274 8276 8412 8413 8414 8276 8126 8128 8415 8416 8417 8128 8127 8130 8418 8277 8419 8130 8129 8132 8131 8420 7833 8132 8131 7833 8420 8279 7985 8420 7985 7833 8279 7989 8281 7985 8279 8281 8421 8136 8422 8281 7989 7988 7987 8423 8282 7988 7987 8282 8423 8135 7992 8423 7992 8282 8135 8284 8285 7992 8135 8285 8284 8424 8286 8285 8284 8286 8424 7996 8287 8286 8424 8287 8425 8288 8426 8287 7996 7995 7994 8427 7839 7995 7994 7839 8427 8290 8291 7839 8427 8291 8290 8428 7842 8291 8290 7842 8428 8429 8295 7842 8428 8295 8429 8430 8296 8296 8295 8429 8430 8431 8297 8296 8430 8297 8431 7847 8298 8297 8431 8298 7847 8432 8299 8299 8298 7847 8432 8433 8300 8299 8432 8300 8433 7705 8301 8300 8433 8301 7705 8434 8302 8302 8301 7705 8434 8435 8303 8303 8302 8434 8435 8436 8151 8151 8303 8435 8436 8304 8307 8151 8436 8307 229 231 8154 8307 8304 8306 230 8308 231 8306 8305 8154 8437 8438 226 8305 229 8154 230 8438 8437 8155 8308 227 8156 231 8308 227 8308 8437 753 227 228 752 758 8157 759 224 221 755 8311 751 8157 757 750 751 757 755 8439 8309 8311 751 8311 8310 8309 8440 8312 8441 8313 8440 8158 8310 8312 8313 8312 8440 8442 8314 8441 8314 8313 8441 8443 8315 8442 8315 8314 8442 8444 8316 8443 8316 8315 8443 8163 8317 8444 8316 8444 8317 8162 8318 8163 8318 8317 8163 8445 8319 8162 8319 8318 8162 7869 8320 8445 8320 8319 8445 7870 7869 8446 7871 8320 7869 8024 8321 7870 8321 7871 7870 8024 8447 8022 8321 8024 8023 8448 8322 8022 8322 8023 8022 8449 8323 8448 8322 8448 8323 8172 8324 8449 8324 8323 8449 8172 8174 8176 8324 8172 8177 8028 8325 8176 8325 8177 8176 8028 8450 8027 8325 8028 7881 8451 7879 8027 7881 8027 7879 8033 8328 8451 8328 7879 8451 8033 8326 8031 8328 8033 8032 8031 8452 8182 8032 8031 8035 8453 8036 8182 8035 8182 8036 8040 8331 8453 8331 8036 8453 8038 8040 8454 8039 8331 8040 8038 8455 8185 8039 8038 8186 8185 8456 8187 8186 8185 7893 8187 8457 8332 7893 8187 7891 8458 8042 8332 7891 8332 8042 8334 8044 8458 8042 8458 8044 8337 8046 8334 8044 8334 8046 8050 8341 8337 8341 8046 8337 8459 8048 8460 8049 8341 8050 8048 8459 8190 8049 8048 8191 8190 8461 8192 8191 8190 8193 8192 8462 8194 8193 8192 8195 8194 8463 8196 8195 8194 8197 8196 8464 8198 8197 8196 8052 8465 8053 8198 8052 8198 8053 8343 8055 8465 8053 8465 8055 8059 8347 8343 8347 8055 8343 8057 8059 8466 8058 8347 8059 8057 8467 8201 8058 8057 8202 8201 8468 8203 8202 8201 8061 8469 8062 8203 8061 8203 8062 8205 8350 8469 8350 8062 8469 8205 8348 8206 8350 8205 7913 8470 7911 8206 7913 8206 7911 8208 8353 8470 8353 7911 8470 8208 8351 8209 8353 8208 8210 8068 8354 8209 8354 8210 8209 8068 8471 8066 8354 8068 8067 7918 8355 8066 8355 8067 8066 7918 8472 7919 8355 7918 7917 7922 8356 7919 8356 7917 7919 7922 8473 7923 8356 7922 7921 8474 8357 7923 8357 7921 7923 7630 8358 8474 8358 8357 8474 7630 8475 7631 8358 7630 7629 8476 8359 7631 8359 7629 7631 8477 7633 8476 7633 8359 8476 8362 7634 8477 7634 7633 8477 8362 8478 8360 7634 8362 8361 8479 8363 8360 8363 8361 8360 8480 8364 8479 8364 8363 8479 8481 8365 8480 8365 8364 8480 8482 8366 8481 8366 8365 8481 8483 8367 8482 8367 8366 8482 8484 8368 8483 8368 8367 8483 8485 8369 8484 8369 8368 8484 8486 8370 8485 8370 8369 8485 8487 8371 8486 8371 8370 8486 8488 8372 8487 8372 8371 8487 8489 8373 8488 8373 8372 8488 8490 8374 8489 8374 8373 8489 8491 8375 8490 8375 8374 8490 8492 8376 8491 8376 8375 8491 8237 8377 8492 8376 8492 8377 8237 8236 8378 8493 8379 8236 8240 8377 8378 8379 8378 8236 8494 7654 8493 7654 8379 8493 8382 7655 8494 7655 7654 8494 8380 8382 8495 8381 7655 8382 8496 8383 8380 8383 8381 8380 8245 8384 8496 8383 8496 8384 8244 8385 8245 8385 8384 8245 7796 8386 8244 8386 8385 8244 7796 8497 7797 8386 7796 7798 7958 8387 7797 8387 7798 7797 7959 7958 8498 8387 7958 7957 8499 7961 7959 7957 7959 7961 8253 8390 8499 8390 7961 8499 8253 8388 8254 8390 8253 8109 8500 8110 8254 8109 8254 8110 8256 8393 8500 8393 8110 8500 8256 8391 8257 8393 8256 7968 8501 7966 8257 7968 8257 7966 8395 8113 8501 7966 8501 8113 8259 8399 8395 8399 8113 8395 8259 8397 8260 8399 8259 8261 8260 8502 8262 8261 8260 8263 8262 8503 8264 8263 8262 8116 8504 8117 8264 8116 8264 8117 8401 8119 8504 8117 8504 8119 8404 8121 8401 8119 8401 8121 8407 8123 8404 8121 8404 8123 8266 8411 8407 8411 8123 8407 8267 8266 8505 8411 8266 8268 8267 8506 8269 8268 8267 8270 8269 8507 8271 8270 8269 8272 8271 8508 8273 8272 8271 8274 8273 8509 8275 8274 8273 8126 8510 8127 8275 8126 8275 8127 8413 8129 8510 8127 8510 8129 8416 8131 8413 8129 8413 8131 8277 8420 8416 8420 8131 8416 8277 8418 8278 8420 8277 8279 8278 8511 8280 8279 8278 7989 8512 7987 8280 7989 8280 7987 8136 8423 8512 8423 7987 8512 8136 8421 8134 8423 8136 8135 8134 8513 8283 8135 8134 8284 8139 8424 8283 8424 8284 8283 8138 8139 8514 8424 8139 7996 8515 7994 8138 7996 8138 7994 8288 8427 8515 8427 7994 8515 8288 8425 8289 8427 8288 8290 8516 8428 8289 8428 8290 8289 8293 8429 8516 8428 8516 8429 8292 8430 8293 8430 8429 8293 7845 8431 8292 8431 8430 8292 7845 8517 7846 8431 7845 7847 8518 8432 7846 8432 7847 7846 7706 8433 8518 8433 8432 8518 7706 8519 7707 8433 7706 7705 8520 8434 7707 8434 7705 7707 8521 8435 8520 8435 8434 8520 8522 8436 8521 8436 8435 8521 8523 8304 8522 8304 8436 8522 8524 8305 8523 8305 8304 8523 8525 229 8524 229 8305 8524 8438 8525 8526 230 229 8525 230 8525 8438 227 8437 225 8308 230 8437 8437 226 225 228 225 224 224 759 758 223 759 221 754 8527 8311 757 759 755 754 8311 755 8311 8527 8439 8439 8528 8309 8309 8528 8440 8528 8529 8440 8440 8529 8441 8529 8530 8441 8441 8530 8442 8530 8531 8442 8531 8532 8443 8531 8443 8442 8532 8533 8444 8532 8444 8443 8533 8534 8163 8533 8163 8444 8161 8163 8534 8161 8535 8162 8535 8536 8445 8535 8445 8162 8536 8537 7869 8536 7869 8445 8446 7869 8537 8446 8538 7870 8538 8447 8024 8538 8024 7870 8447 8539 8022 8539 8540 8022 8540 8541 8448 8540 8448 8022 8541 8542 8449 8541 8449 8448 8173 8449 8542 8173 8172 8449 8174 8543 8176 8543 8544 8176 8544 8450 8028 8544 8028 8176 8450 8545 8027 8545 8546 8027 8546 8547 8451 8546 8451 8027 8327 8451 8547 8327 8033 8451 8326 8548 8031 8548 8452 8031 8452 8549 8182 8549 8550 8182 8550 8551 8453 8550 8453 8182 8330 8453 8551 8330 8040 8453 8454 8040 8329 8454 8455 8038 8455 8552 8185 8552 8456 8185 8456 8553 8187 8553 8457 8187 8457 8554 8332 8554 8555 8332 8555 8556 8458 8555 8458 8332 8335 8458 8556 8335 8334 8458 8338 8334 8333 8338 8337 8334 8340 8337 8336 8340 8050 8337 8460 8050 8339 8460 8048 8050 8459 8557 8190 8557 8461 8190 8461 8558 8192 8558 8462 8192 8462 8559 8194 8559 8463 8194 8463 8560 8196 8560 8464 8196 8464 8561 8198 8561 8562 8198 8562 8563 8465 8562 8465 8198 8344 8465 8563 8344 8343 8465 8346 8343 8342 8346 8059 8343 8466 8059 8345 8466 8467 8057 8467 8564 8201 8564 8468 8201 8468 8565 8203 8565 8566 8203 8566 8567 8469 8566 8469 8203 8349 8469 8567 8349 8205 8469 8348 8568 8206 8568 8569 8206 8569 8570 8470 8569 8470 8206 8352 8470 8570 8352 8208 8470 8351 8571 8209 8571 8572 8209 8572 8471 8068 8572 8068 8209 8471 8573 8066 8573 8574 8066 8574 8472 7918 8574 7918 8066 8472 8575 7919 8575 8576 7919 8576 8473 7922 8576 7922 7919 8473 8577 7923 8577 8578 7923 8578 8579 8474 8578 8474 7923 8579 8475 7630 8579 7630 8474 8475 8580 7631 8580 8581 7631 7631 8581 8476 8581 8582 8476 8582 8583 8477 8582 8477 8476 8583 8478 8362 8583 8362 8477 8478 8584 8360 8584 8585 8360 8360 8585 8479 8585 8586 8479 8479 8586 8480 8586 8587 8480 8480 8587 8481 8587 8588 8481 8588 8589 8482 8588 8482 8481 8589 8590 8483 8589 8483 8482 8590 8591 8484 8590 8484 8483 8591 8592 8485 8591 8485 8484 8592 8593 8486 8592 8486 8485 8593 8594 8487 8593 8487 8486 8594 8595 8488 8594 8488 8487 8595 8596 8489 8595 8489 8488 8596 8597 8490 8596 8490 8489 8597 8598 8491 8597 8491 8490 8598 8599 8492 8598 8492 8491 8599 8600 8237 8599 8237 8492 8235 8237 8600 8235 8601 8236 8236 8601 8493 8601 8602 8493 8602 8603 8494 8602 8494 8493 8603 8604 8382 8603 8382 8494 8495 8382 8604 8495 8605 8380 8605 8606 8496 8605 8496 8380 8606 8607 8245 8606 8245 8496 8246 8245 8607 8246 8608 8244 8608 8497 7796 8608 7796 8244 8497 8609 7797 8609 8610 7797 8610 8611 7958 8610 7958 7797 7958 8611 8498 8498 8612 7959 8612 8613 8499 8612 8499 7959 8389 8499 8613 8389 8253 8499 8388 8614 8254 8614 8615 8254 8615 8616 8500 8615 8500 8254 8392 8500 8616 8392 8256 8500 8391 8617 8257 8617 8618 8257 8618 8619 8501 8618 8501 8257 8396 8501 8619 8396 8395 8501 8398 8395 8394 8398 8259 8395 8397 8620 8260 8620 8502 8260 8502 8621 8262 8621 8503 8262 8503 8622 8264 8622 8623 8264 8623 8624 8504 8623 8504 8264 8402 8504 8624 8402 8401 8504 8405 8401 8400 8405 8404 8401 8408 8404 8403 8408 8407 8404 8410 8407 8406 8410 8266 8407 8266 8409 8505 8505 8506 8267 8506 8625 8269 8625 8507 8269 8507 8626 8271 8626 8508 8271 8508 8627 8273 8627 8509 8273 8509 8628 8275 8628 8629 8275 8629 8630 8510 8629 8510 8275 8414 8510 8630 8414 8413 8510 8417 8413 8412 8417 8416 8413 8419 8416 8415 8419 8277 8416 8418 8631 8278 8631 8511 8278 8511 8632 8280 8632 8633 8280 8633 8634 8512 8633 8512 8280 8422 8512 8634 8422 8136 8512 8421 8635 8134 8635 8513 8134 8513 8636 8283 8636 8637 8283 8637 8638 8139 8637 8139 8283 8139 8638 8514 8514 8639 8138 8639 8640 8515 8639 8515 8138 8426 8515 8640 8426 8288 8515 8425 8641 8289 8641 8642 8289 8642 8643 8516 8642 8516 8289 8643 8644 8293 8643 8293 8516 8294 8293 8644 8294 8645 8292 8645 8517 7845 8645 7845 8292 8517 8646 7846 8646 8647 7846 8647 8648 8518 8647 8518 7846 8648 8519 7706 8648 7706 8518 8519 8649 7707 8649 8650 7707 7707 8650 8520 8650 8651 8520 8651 8652 8521 8651 8521 8520 8652 8653 8522 8652 8522 8521 8653 8654 8523 8653 8523 8522 8654 8655 8524 8654 8524 8523 8655 8526 8525 8655 8525 8524 8526 8656 8438 8656 8657 8438 8438 8657 226 8657 8658 226 221 224 222 226 8658 222 223 222 8658 8659 8660 8661 8662 8663 8664 8665 8666 8667 8668 8669 8670 8671 8672 8673 8674 8675 8676 8677 8678 8679 8680 8681 8682 8683 8684 8685 8686 8687 8688 8689 8690 8691 8692 8693 8694 8695 8696 8697 8698 8699 8700 8701 8702 8703 8704 8705 8706 8707 8708 8709 8710 8711 8712 8713 8714 8715 8716 8717 8718 8719 8720 8721 8722 8723 8724 8725 8726 8727 8728 8729 8730 8731 8732 8733 8734 8735 8736 8737 8738 8739 8740 8741 8742 8743 8744 8745 8746 8747 8748 8749 8750 8751 8752 8753 8754 8755 8756 8757 8758 8759 8760 8761 8762 8763 8764 8765 8766 8767 8768 8769 8770 8771 8772 8773 8774 8775 8776 8777 8778 8779 8780 8781 8782 8783 8784 8785 8786 8787 8788 8789 8790 8791 8792 8793 8794 8795 8796 8797 8798 8799 8800 8801 8802 8803 8804 8805 8806 8807 8808 8809 8810 8811 8812 8813 8814 8815 8816 8817 8818 8819 8820 8821 8822 8823 8824 8825 8826 8827 8828 8829 8830 8831 8832 8833 8834 8835 8836 8837 8838 8839 8840 8841 8842 8843 8844 8845 8846 8847 8848 8849 8850 8851 8852 8853 8854 8855 8856 8857 8858 8859 8860 8861 8862 8863 8864 8865 8866 8867 8868 8869 8870 8871 8872 8873 8874 8875 8876 8877 8878 8879 8880 8881 8882 8883 8884 8885 8886 8887 8888 8889 8890 8891 8892 8893 8894 8895 8896 8897 8898 8899 8900 8901 8902 8903 8904 8905 8906 8907 8908 8909 8910 8911 8912 8913 8914 8915 8916 8917 8918 8919 8920 8921 8922 8923 8924 8925 8926 8927 8928 8929 8930 8931 8932 8933 8934 8935 8936 8937 8938 8939 8940 8941 8942 8943 8944 8945 8946 8947 8948 8949 8950 8951 8952 8953 8954 8955 8956 8957 8958 8959 8960 8961 8962 8963 8964 8965 8966 8967 8968 8969 8970 8971 8972 8973 8974 8975 8976 8977 8978 8979 8980 8981 8982 8983 8984 8985 8986 8987 8988 8989 8990 8991 8992 8993 8994 8995 8996 8997 8997 8998 8995 8999 9000 8996 8997 8996 9000 9001 8999 9002 8999 9001 9000 9002 9003 9004 9004 9001 9002 9005 9006 9003 9004 9003 9006 9007 9005 9008 9005 9007 9006 9008 9009 9010 9010 9007 9008 9011 9012 9009 9010 9009 9012 9013 9011 9014 9011 9013 9012 9014 9015 9016 9016 9013 9014 9017 9018 9015 9016 9015 9018 9019 9017 9020 9017 9019 9018 9020 9021 9022 9022 9019 9020 9023 9024 9021 9022 9021 9024 9025 9023 9026 9023 9025 9024 9026 9027 9028 9028 9025 9026 9029 9030 9027 9028 9027 9030 9031 9029 9032 9029 9031 9030 9032 9033 9034 9034 9031 9032 9035 9036 9033 9034 9033 9036 9037 9035 9038 9035 9037 9036 9038 9039 9040 9040 9037 9038 9041 9042 9039 9040 9039 9042 9043 9041 9044 9041 9043 9042 9044 9045 9046 9046 9043 9044 9047 9048 9045 9046 9045 9048 9049 9047 9050 9047 9049 9048 9050 9051 9052 9052 9049 9050 9053 9054 9051 9052 9051 9054 9055 9053 9056 9053 9055 9054 9056 9057 9058 9058 9055 9056 9059 9060 9057 9058 9057 9060 9061 9059 9062 9059 9061 9060 9062 9063 9064 9064 9061 9062 9065 9066 9063 9064 9063 9066 9067 9065 9068 9065 9067 9066 9068 9069 9070 9070 9067 9068 9071 9072 9069 9070 9069 9072 9073 9071 9074 9071 9073 9072 9074 9075 9076 9076 9073 9074 9077 9078 9075 9076 9075 9078 9079 9077 9080 9077 9079 9078 9080 9081 9082 9082 9079 9080 9083 9084 9081 9082 9081 9084 9085 9083 9086 9083 9085 9084 9086 9087 9088 9088 9085 9086 9089 9090 9087 9088 9087 9090 9091 9089 9092 9089 9091 9090 9092 9093 9094 9094 9091 9092 9095 9096 9093 9094 9093 9096 9097 9095 9098 9095 9097 9096 9098 9099 9100 9100 9097 9098 9101 9102 9099 9100 9099 9102 9103 9101 9104 9101 9103 9102 9104 9105 9106 9106 9103 9104 8662 8664 9105 9106 9105 8664 8998 8991 8990 8990 8995 8998 8989 8994 8993 8989 8991 8994 8992 8984 8983 8993 8992 8983 8987 8986 8985 8984 8987 8985 8977 8979 8988 8988 8979 8986 8982 8978 8980 8980 8978 8977 8972 8981 8973 8972 8982 8981 8971 8976 8975 8971 8973 8976 8974 8966 8965 8975 8974 8965 8969 8968 8967 8966 8969 8967 8959 8961 8970 8970 8961 8968 8964 8960 8962 8962 8960 8959 8954 8963 8955 8954 8964 8963 8953 8958 8957 8953 8955 8958 8956 8948 8947 8957 8956 8947 8951 8950 8949 8948 8951 8949 8941 8943 8952 8952 8943 8950 8946 8942 8944 8944 8942 8941 8936 8945 8937 8936 8946 8945 8935 8940 8939 8935 8937 8940 8938 8930 8929 8939 8938 8929 8933 8932 8931 8930 8933 8931 8923 8925 8934 8934 8925 8932 8928 8924 8926 8926 8924 8923 8918 8927 8919 8918 8928 8927 8917 8922 8921 8917 8919 8922 8920 8912 8911 8921 8920 8911 8915 8914 8913 8912 8915 8913 8905 8907 8916 8916 8907 8914 8910 8906 8908 8908 8906 8905 8900 8909 8901 8900 8910 8909 8899 8904 8903 8899 8901 8904 8902 8894 8893 8903 8902 8893 8897 8896 8895 8894 8897 8895 8887 8889 8898 8898 8889 8896 8892 8888 8890 8890 8888 8887 8882 8891 8883 8882 8892 8891 8881 8886 8885 8881 8883 8886 8884 8876 8875 8885 8884 8875 8879 8878 8877 8876 8879 8877 8869 8871 8880 8880 8871 8878 8874 8870 8872 8872 8870 8869 8864 8873 8865 8864 8874 8873 8863 8868 8867 8863 8865 8868 8866 8858 8857 8867 8866 8857 8861 8860 8859 8858 8861 8859 8851 8853 8862 8862 8853 8860 8856 8852 8854 8854 8852 8851 8846 8855 8847 8846 8856 8855 8845 8850 8849 8845 8847 8850 8848 8840 8839 8849 8848 8839 8843 8842 8841 8840 8843 8841 8833 8835 8844 8844 8835 8842 8838 8834 8836 8836 8834 8833 8828 8837 8829 8828 8838 8837 8827 8832 8831 8827 8829 8832 8830 8822 8821 8831 8830 8821 8825 8824 8823 8822 8825 8823 8815 8817 8826 8826 8817 8824 8820 8816 8818 8818 8816 8815 8810 8819 8811 8810 8820 8819 8809 8814 8813 8809 8811 8814 8812 8804 8803 8813 8812 8803 8807 8806 8805 8804 8807 8805 8797 8799 8808 8808 8799 8806 8802 8798 8800 8800 8798 8797 8792 8801 8793 8792 8802 8801 8791 8796 8795 8791 8793 8796 8794 8786 8785 8795 8794 8785 8789 8788 8787 8786 8789 8787 8779 8781 8790 8790 8781 8788 8784 8780 8782 8782 8780 8779 8774 8783 8775 8774 8784 8783 8773 8778 8777 8773 8775 8778 8776 8768 8767 8777 8776 8767 8771 8770 8769 8768 8771 8769 8761 8763 8772 8772 8763 8770 8766 8762 8764 8764 8762 8761 8756 8765 8757 8756 8766 8765 8755 8760 8759 8755 8757 8760 8758 8750 8749 8759 8758 8749 8753 8752 8751 8750 8753 8751 8743 8745 8754 8754 8745 8752 8748 8744 8746 8746 8744 8743 8738 8747 8739 8738 8748 8747 8737 8742 8741 8737 8739 8742 8740 8732 8731 8741 8740 8731 8735 8734 8733 8732 8735 8733 8725 8727 8736 8736 8727 8734 8730 8726 8728 8728 8726 8725 8720 8729 8721 8720 8730 8729 8719 8724 8723 8719 8721 8724 8722 8714 8713 8723 8722 8713 8717 8716 8715 8714 8717 8715 8707 8709 8718 8718 8709 8716 8712 8708 8710 8710 8708 8707 8702 8711 8703 8702 8712 8711 8701 8706 8705 8701 8703 8706 8704 8696 8695 8705 8704 8695 8699 8698 8697 8696 8699 8697 8689 8691 8700 8700 8691 8698 8694 8690 8692 8692 8690 8689 8684 8693 8685 8684 8694 8693 8683 8688 8687 8683 8685 8688 8686 8678 8677 8687 8686 8677 8681 8680 8679 8678 8681 8679 8671 8673 8682 8682 8673 8680 8676 8672 8674 8674 8672 8671 8666 8675 8667 8666 8676 8675 8665 8668 8670 8665 8667 8668 8669 8659 8661 8670 8669 8661 8663 8662 8660 8659 8663 8660

-
-
-
-
- - - - - - 1 0 0 0 0 -1.11022e-16 -1 0 0 1 -1.11022e-16 0 0 0 0 1 - - - - 1 0 0 0 0 1.11022e-16 1 0 0 -1 1.11022e-16 0 0 0 0 1 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/src/tsukuba2022/models/barricade/model.config b/src/tsukuba2022/models/barricade/model.config deleted file mode 100644 index 22ad1be..0000000 --- a/src/tsukuba2022/models/barricade/model.config +++ /dev/null @@ -1,5 +0,0 @@ - - barricade - 1.0 - model.sdf - diff --git a/src/tsukuba2022/models/barricade/model.sdf b/src/tsukuba2022/models/barricade/model.sdf deleted file mode 100644 index 0db1667..0000000 --- a/src/tsukuba2022/models/barricade/model.sdf +++ /dev/null @@ -1,33 +0,0 @@ - - - - True - - - 0 0 1.5 0 0 0 - - - - 3 0.5 3 - - - - - - - - - - - 3 0.5 3 - - - - - - - - diff --git a/src/tsukuba2022/models/course/materials/scripts/course.material b/src/tsukuba2022/models/course/materials/scripts/course.material deleted file mode 100644 index 7896c40..0000000 --- a/src/tsukuba2022/models/course/materials/scripts/course.material +++ /dev/null @@ -1,13 +0,0 @@ -material course -{ - technique - { - pass - { - texture_unit - { - texture igvc2022_course_image_1400x1200.png - } - } - } -} diff --git a/src/tsukuba2022/models/course/materials/textures/igvc2022_course_image_1400x1200.png b/src/tsukuba2022/models/course/materials/textures/igvc2022_course_image_1400x1200.png deleted file mode 100644 index d35abc4..0000000 --- a/src/tsukuba2022/models/course/materials/textures/igvc2022_course_image_1400x1200.png +++ /dev/null Binary files differ diff --git a/src/tsukuba2022/models/course/materials/textures/igvc2022_course_image_v2_1400x1200.png b/src/tsukuba2022/models/course/materials/textures/igvc2022_course_image_v2_1400x1200.png deleted file mode 100644 index 72f0136..0000000 --- a/src/tsukuba2022/models/course/materials/textures/igvc2022_course_image_v2_1400x1200.png +++ /dev/null Binary files differ diff --git a/src/tsukuba2022/models/course/model.config b/src/tsukuba2022/models/course/model.config deleted file mode 100644 index 37d6e2e..0000000 --- a/src/tsukuba2022/models/course/model.config +++ /dev/null @@ -1,5 +0,0 @@ - - course - 1.0 - model.sdf - diff --git a/src/tsukuba2022/models/course/model.sdf b/src/tsukuba2022/models/course/model.sdf deleted file mode 100644 index f2947b1..0000000 --- a/src/tsukuba2022/models/course/model.sdf +++ /dev/null @@ -1,42 +0,0 @@ - - - - true - - - - - - - 43 37 - - - - - - - - - - - 43 37 - - - - - - 1 - 1 - - - - - - - - - diff --git a/src/tsukuba2022/models/course_v2/materials/scripts/course_v2.material b/src/tsukuba2022/models/course_v2/materials/scripts/course_v2.material deleted file mode 100644 index ef84cca..0000000 --- a/src/tsukuba2022/models/course_v2/materials/scripts/course_v2.material +++ /dev/null @@ -1,13 +0,0 @@ -material course_v2 -{ - technique - { - pass - { - texture_unit - { - texture igvc2022_course_image_v2_1400x1200.png - } - } - } -} diff --git a/src/tsukuba2022/models/course_v2/materials/textures/igvc2022_course_image_v2_1400x1200.png b/src/tsukuba2022/models/course_v2/materials/textures/igvc2022_course_image_v2_1400x1200.png deleted file mode 100644 index 72f0136..0000000 --- a/src/tsukuba2022/models/course_v2/materials/textures/igvc2022_course_image_v2_1400x1200.png +++ /dev/null Binary files differ diff --git a/src/tsukuba2022/models/course_v2/model.config b/src/tsukuba2022/models/course_v2/model.config deleted file mode 100644 index afb5e2c..0000000 --- a/src/tsukuba2022/models/course_v2/model.config +++ /dev/null @@ -1,5 +0,0 @@ - - course_v2 - 1.0 - model.sdf - diff --git a/src/tsukuba2022/models/course_v2/model.sdf b/src/tsukuba2022/models/course_v2/model.sdf deleted file mode 100644 index 687723e..0000000 --- a/src/tsukuba2022/models/course_v2/model.sdf +++ /dev/null @@ -1,41 +0,0 @@ - - - true - - - - - - - 43 37 - - - - - - - - - - - 43 37 - - - - - - 1 - 1 - - - - - - - - - diff --git a/src/tsukuba2022/models/ramp/model.config b/src/tsukuba2022/models/ramp/model.config deleted file mode 100644 index d0b4039..0000000 --- a/src/tsukuba2022/models/ramp/model.config +++ /dev/null @@ -1,5 +0,0 @@ - - ramp - 1.0 - model.sdf - diff --git a/src/tsukuba2022/models/ramp/model.sdf b/src/tsukuba2022/models/ramp/model.sdf deleted file mode 100644 index 38884e5..0000000 --- a/src/tsukuba2022/models/ramp/model.sdf +++ /dev/null @@ -1,73 +0,0 @@ - - - - True - - - 0 -0.9889 0.1484 0.148 0 0 - - - - 4 2 0.05 - - - - - - - - - - - 4 2 0.05 - - - - - - 2 - 2 - - - - - - - - 0 0.9889 0.1484 -0.148 0 0 - - - - 4 2 0.05 - - - - - - - - - - - 4 2 0.05 - - - - - - 2 - 2 - - - - - - - - diff --git a/src/tsukuba2022/multimaps/nakaniwa/map0.pgm b/src/tsukuba2022/multimaps/nakaniwa/map0.pgm new file mode 100644 index 0000000..df54984 --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa/map0.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/nakaniwa/map0.yaml b/src/tsukuba2022/multimaps/nakaniwa/map0.yaml new file mode 100644 index 0000000..a512b8c --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa/map0.yaml @@ -0,0 +1,6 @@ +image: ./map0.pgm +resolution: 0.05 +origin: [-50.0, -50.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/nakaniwa/map1.pgm b/src/tsukuba2022/multimaps/nakaniwa/map1.pgm new file mode 100644 index 0000000..27281a6 --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa/map1.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/nakaniwa/map1.yaml b/src/tsukuba2022/multimaps/nakaniwa/map1.yaml new file mode 100644 index 0000000..3a4d442 --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa/map1.yaml @@ -0,0 +1,6 @@ +image: ./map1.pgm +resolution: 0.05 +origin: [-47.831295, -50.394739, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/nakaniwa/merged_map.pgm b/src/tsukuba2022/multimaps/nakaniwa/merged_map.pgm new file mode 100644 index 0000000..0c59c4c --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa/merged_map.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/nakaniwa/merged_map.yaml b/src/tsukuba2022/multimaps/nakaniwa/merged_map.yaml new file mode 100644 index 0000000..5e0cd83 --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa/merged_map.yaml @@ -0,0 +1,6 @@ +image: ./merged_map.pgm +resolution: 0.05 +origin: [-50.0, -50.39473899999999, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/nakaniwa/waypoints.yaml b/src/tsukuba2022/multimaps/nakaniwa/waypoints.yaml new file mode 100644 index 0000000..463830a --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa/waypoints.yaml @@ -0,0 +1,33 @@ +waypoints: +- point: {x: 4.8992, y: 0.0763934, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 11.025331, y: -0.023422, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 18.50064, y: -0.394513, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 26.176818, y: -0.880348, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.8965, y: -2.35386, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.74376, y: -4.864187, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 50.530069, y: -5.066462, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 53.505717, y: -1.933611, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.2674, y: 7.98859, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 53.0977, y: 20.0885, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.5512, y: 29.5179, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 52.298734, y: 41.727943, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 52.033145, y: 52.371588, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 50, y: 54.5, z: 0, vel: 1, rad: 1, stop: true, change_map: 1} +- point: {x: 44.457458, y: 54.265651, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 38.331208, y: 54.17344, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 30.568212, y: 54.0757, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 22.183928, y: 53.966732, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 14.496347, y: 53.725704, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 6.34269, y: 53.623967, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -0.732295, y: 53.479098, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -3.648502, y: 50.77132, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -3.260954, y: 43.319186, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -2.632884, y: 33.104345, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -2.248518, y: 23.345314, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -2.22096, y: 11.492785, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -2.253471, y: 0.890283, z: 0.0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1663209268.6905353, frame_id: map} + pose: + position: {x: 1.084303876129681, y: -1.5445686660287592, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.012634000199744012, w: 0.9999201878344856} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/nakaniwa_sim/map0.pgm b/src/tsukuba2022/multimaps/nakaniwa_sim/map0.pgm new file mode 100644 index 0000000..2f5060c --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa_sim/map0.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/nakaniwa_sim/map0.yaml b/src/tsukuba2022/multimaps/nakaniwa_sim/map0.yaml new file mode 100644 index 0000000..a47e244 --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa_sim/map0.yaml @@ -0,0 +1,6 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/multimaps/nakaniwa_sim/map0.pgm +resolution: 0.05 +origin: [-60.0, -60.0, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/nakaniwa_sim/map1.pgm b/src/tsukuba2022/multimaps/nakaniwa_sim/map1.pgm new file mode 100644 index 0000000..4d2389a --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa_sim/map1.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/nakaniwa_sim/map1.yaml b/src/tsukuba2022/multimaps/nakaniwa_sim/map1.yaml new file mode 100644 index 0000000..71a1f95 --- /dev/null +++ b/src/tsukuba2022/multimaps/nakaniwa_sim/map1.yaml @@ -0,0 +1,6 @@ +image: /home/ubuntu/catkin_ws/src/tsukuba2022/multimaps/nakaniwa_sim/map1.pgm +resolution: 0.05 +origin: [-45.050354, -43.236632, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map0.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map0.pgm new file mode 100644 index 0000000..54804db --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map0.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map0.yaml new file mode 100644 index 0000000..def5cbe --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map0.yaml @@ -0,0 +1,6 @@ +image: ./map0.pgm +resolution: 0.1 +origin: [-110.8, -78.8, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map1.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map1.pgm new file mode 100644 index 0000000..06cbc76 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map1.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map1.yaml new file mode 100644 index 0000000..1aeb63f --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map1.yaml @@ -0,0 +1,6 @@ +image: ./map1.pgm +resolution: 0.1 +origin: [-288.393131, -87.22861, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map2.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map2.pgm new file mode 100644 index 0000000..5ea407d --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map2.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map2.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map2.yaml new file mode 100644 index 0000000..68c44ff --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map2.yaml @@ -0,0 +1,6 @@ +image: ./map2.pgm +resolution: 0.1 +origin: [-549.081788, -28.869566, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map3.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map3.pgm new file mode 100644 index 0000000..9aca87b --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map3.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map3.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map3.yaml new file mode 100644 index 0000000..3afef19 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map3.yaml @@ -0,0 +1,6 @@ +image: ./map3.pgm +resolution: 0.1 +origin: [-602.157905, 58.832836, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map4.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map4.pgm new file mode 100644 index 0000000..7b3b926 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map4.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map4.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map4.yaml new file mode 100644 index 0000000..375dcca --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map4.yaml @@ -0,0 +1,6 @@ +image: ./map4.pgm +resolution: 0.1 +origin: [-657.166625, 78.101689, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map5.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map5.pgm new file mode 100644 index 0000000..1e2877f --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map5.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map5.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map5.yaml new file mode 100644 index 0000000..34a70da --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map5.yaml @@ -0,0 +1,6 @@ +image: ./map5.pgm +resolution: 0.1 +origin: [-636.88789, 228.367456, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map6.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map6.pgm new file mode 100644 index 0000000..5f3b43f --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map6.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map6.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map6.yaml new file mode 100644 index 0000000..fa0a194 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map6.yaml @@ -0,0 +1,6 @@ +image: ./map6.pgm +resolution: 0.1 +origin: [-494.929449, 7.12399, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map7.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/map7.pgm new file mode 100644 index 0000000..b18ad55 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map7.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/map7.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/map7.yaml new file mode 100644 index 0000000..6a019c7 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/map7.yaml @@ -0,0 +1,6 @@ +image: ./map7.pgm +resolution: 0.1 +origin: [-426.580826, -17.472845, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/merged_map_1-8.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba/merged_map_1-8.pgm new file mode 100644 index 0000000..e8e8688 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/merged_map_1-8.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/merged_map_1-8.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/merged_map_1-8.yaml new file mode 100644 index 0000000..74f5ce0 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/merged_map_1-8.yaml @@ -0,0 +1,6 @@ +image: ./merged_map_1-8.pgm +resolution: 0.1 +origin: [-657.166625164207, -87.22861015928396, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints.yaml new file mode 100644 index 0000000..693d4de --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints.yaml @@ -0,0 +1,433 @@ +waypoints: +- point: {x: 4.09724, y: 0.504168, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.659, y: 1.14789, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 20.5776, y: 1.30268, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.2563, y: 1.64634, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 38.1161, y: 1.91456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.2937, y: 1.73542, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.5451, y: 1.66404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 58.0735, y: 0.128874, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 61.313, y: -6.31239, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.9454, y: -14.2518, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.6144, y: -15.4014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.316, y: -15.5441, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.2391, y: -15.3596, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 77.357, y: -15.2531, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 79.101358, y: -15.32212, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.470272, y: -16.227709, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 81.691765, y: -17.449202, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 83.0514, y: -18.1883, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 85.4238, y: -18.5438, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.9159, y: -17.5321, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.2617, y: -15.0813, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.16, y: -10.9362, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.0087, y: -6.39951, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.8094, y: -2.38376, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.683, y: 3.18917, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 84.1737, y: 4.69392, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.0329, y: 4.54753, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.1995, y: 2.24651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.9941, y: -0.0748514, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.1423, y: -4.43719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 59.449401, y: -7.597903, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.4954, y: -9.77409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 51.7554, y: -10.206, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.1474, y: -10.3002, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 46.051, y: -11.3614, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.5089, y: -11.9516, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 37.4443, y: -12.0861, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 35.2285, y: -12.1586, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.8879, y: -14.2313, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.7788, y: -17.3731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.519273, y: -19.091731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.243205, y: -19.061404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 23.785178, y: -19.00075, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 21.2425, y: -18.9706, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.1694, y: -19.0082, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 17.5523, y: -18.9316, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 15.426, y: -18.7627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 12.495, y: -18.5628, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 10.0156, y: -18.6638, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 7.32172, y: -18.6572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 6.06788, y: -21.9222, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 5.40629, y: -26.6174, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 0.550092, y: -27.6913, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -5.94073, y: -28.0941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -10.5427, y: -28.3094, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -16.6638, y: -28.2209, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -23.255, y: -28.019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -34.563433, y: -33.284636, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -43.9865, y: -35.5365, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -49.5035, y: -37.0547, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -59.2588, y: -38.328, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -65.997293, y: -37.687546, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -74.861316, y: -36.722816, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -78.968532, y: -36.718417, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -83.75627, y: -36.856869, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -88.925109, y: -36.80009, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -98.145582, y: -36.858084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -105.729932, y: -37.112591, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -112.827094, y: -37.178238, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -119.614722, y: -36.806496, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -125.185643, y: -37.034113, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -136.390826, y: -39.014177, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -142.776059, y: -38.943692, z: 0, vel: 1, rad: 0.8, stop: true} +- point: {x: -151.30381, y: -38.555669, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -156.31217, y: -38.560155, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -163.008984, y: -38.679659, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -170.633876, y: -38.925466, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -178.163055, y: -39.056873, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -186.167354, y: -39.218148, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -192.194294, y: -37.156126, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -199.637462, y: -37.243308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -206.68365, y: -37.172295, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -213.963337, y: -36.947721, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -219.989733, y: -36.657375, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -225.740345, y: -39.515697, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.145509, y: -33.082141, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -230.035577, y: -28.839193, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.883482, y: -23.875298, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.837519, y: -15.687723, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.753517, y: -7.754537, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.822194, y: -2.821888, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.724764, y: 1.391393, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.687153, y: 7.635213, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.532438, y: 11.101565, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.571416, y: 15.277872, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.641011, y: 22.795954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.608802, y: 26.524621, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.84853, y: 32.493456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.567279, y: 34.716681, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.672466, y: 37.262953, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.796547, y: 39.658066, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.198126, y: 41.696698, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.193767, y: 43.152423, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -233.670353, y: 45.568782, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -247.758964, y: 45.75834, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.321939, y: 42.876876, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.797814, y: 32.789915, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -253.5219939015618, y: 32.55980001412175, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -258.053394, y: 29.890619, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -264.168789, y: 29.17392, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -270.693645, y: 28.611301, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -277.691194, y: 28.668496, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -283.610716, y: 28.529514, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -288.410126, y: 28.1954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -291.940999, y: 28.013434, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -299.442501, y: 27.529333, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -304.259884, y: 27.396202, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -311.681235, y: 26.983278, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -317.613147, y: 26.511184, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -319.976311, y: 26.535241, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -326.660905, y: 26.111805, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -332.427465, y: 25.81337, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -336.962273, y: 28.125288, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -344.737269, y: 28.01525, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -349.460252, y: 27.871153, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.480806, y: 27.908136, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -362.737053, y: 27.714504, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -372.583986, y: 27.593499, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -378.874107, y: 26.967331, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -382.138561, y: 26.787573, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -393.261261, y: 25.868445, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.538061, y: 25.44106, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -407.076689, y: 25.207773, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -415.964264, y: 24.658856, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -419.724021, y: 24.418726, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -424.37104, y: 24.352715, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -434.608025, y: 23.505254, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -442.741447, y: 22.684765, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -450.938911, y: 22.513319, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -458.383171, y: 22.127258, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -464.87087, y: 21.984709, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -468.132469, y: 21.626119, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -471.323492, y: 21.55016, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.336647, y: 21.889659, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -477.32265, y: 21.631686, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -481.47698, y: 21.16945, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -486.159348, y: 20.094339, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -490.825029, y: 19.257699, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -495.633463, y: 19.876072, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -500.004502, y: 19.663624, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -505.576354, y: 19.511281, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -510.23767, y: 18.403005, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -513.243141, y: 17.497047, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -518.04732, y: 17.25395, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -522.318997, y: 18.216145, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.181251, y: 21.720748, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.220418, y: 26.772257, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.730054, y: 31.445867, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.787967, y: 35.524397, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.605593, y: 40.106628, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.145867, y: 42.598064, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -522.391933, y: 43.761488, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -518.116883, y: 44.938371, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -512.948437, y: 45.116464, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -506.716044, y: 43.861395, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -500.243992, y: 46.981211, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -493.962431, y: 47.201147, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -488.787598, y: 47.437265, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -482.293905, y: 47.603487, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -475.602806, y: 47.550518, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -468.045147, y: 47.973646, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -462.835636, y: 48.192481, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -456.502336, y: 48.500156, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -451.722115, y: 48.901493, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.717969, y: 48.654826, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.602746, y: 48.754387, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -438.877463, y: 48.517506, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -432.316376, y: 49.179618, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -426.472211, y: 49.544632, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -419.409104, y: 50.203781, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -414.692869, y: 50.466941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -410.344484, y: 50.498807, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -405.509605, y: 50.725226, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -399.29213, y: 50.99345, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -395.811454, y: 50.947499, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -391.480197, y: 51.048554, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.324064, y: 51.224959, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -383.675982, y: 50.912722, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.836947, y: 49.929266, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -377.70745, y: 52.005824, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -377.105479, y: 60.481631, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.2159677819452, y: 67.59687010838871, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -375.996853, y: 71.58048, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.816357, y: 74.785425, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.776873, y: 79.972962, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.784127, y: 83.324964, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.948441, y: 87.238649, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.878229, y: 93.223836, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.75997, y: 100.252255, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.124383, y: 104.698424, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.183786, y: 109.935906, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.966584, y: 115.373864, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.046354, y: 118.958734, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.041771, y: 123.005498, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.714012, y: 128.267064, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.761426, y: 131.831983, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.889254, y: 134.273015, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -379.594506, y: 135.135863, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -384.304822, y: 134.561862, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.666492, y: 135.025177, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -392.6819, y: 134.322875, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -396.752025, y: 134.188627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -400.273072, y: 134.798615, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -404.957435, y: 134.349375, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -404.544916, y: 133.998821, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -409.164332, y: 133.857758, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -413.239594, y: 133.695817, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -416.906021, y: 133.46068, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -420.123743, y: 133.306324, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -426.270839, y: 133.578248, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -430.975705, y: 133.686245, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -437.040996, y: 133.57616, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.115877, y: 133.507738, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -443.508932, y: 133.334966, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.877453, y: 133.559804, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -450.496813, y: 133.656158, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -455.38663, y: 133.768045, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -460.454056, y: 133.458128, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -471.108747, y: 133.712433, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.453845, y: 133.777743, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -480.076059, y: 133.413976, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -483.066964, y: 133.308488, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -488.377362, y: 133.33122, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -491.634572, y: 133.459615, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -495.195347, y: 133.423018, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -498.54888, y: 133.45007, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -501.899703, y: 134.280135, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -506.267554, y: 134.827364, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -511.337918, y: 133.557358, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -515.911679, y: 133.469308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -520.426659, y: 135.057578, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -524.680573, y: 135.221091, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -536.04867, y: 135.811884, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -547.472381, y: 135.240112, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -550.969299, y: 135.083822, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -560.372569, y: 134.952614, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -566.098996, y: 135.102915, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -571.366929, y: 133.532739, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -578.328994, y: 133.710034, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -584.532392, y: 135.903225, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -588.113016943929, y: 138.6890288736552, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -588.331708, y: 143.57969, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -588.1925, y: 151.281553, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -587.8078, y: 156.198734, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -587.546379, y: 159.623015, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -587.369936, y: 163.207274, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.917233, y: 167.0085, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.292124, y: 171.255572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.889245, y: 176.106561, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.566909, y: 179.992549, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.570464, y: 184.540065, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.748241, y: 188.41317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.184276, y: 195.07826, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.280951, y: 199.935042, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.517487, y: 206.929981, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.401481, y: 210.598052, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.140378, y: 215.167657, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.057455, y: 219.181678, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.502373, y: 222.531465, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.164629, y: 225.964978, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -584.347585, y: 230.585385, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.606556, y: 234.611835, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.474776, y: 239.329366, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.438094, y: 243.883497, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.091327, y: 249.375227, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.557588, y: 254.336429, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.623731, y: 259.121231, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.964634, y: 264.439564, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.422049, y: 269.12651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.755804, y: 272.414019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.940492, y: 277.146227, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -580.627806, y: 283.714641, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -576.0559809514564, y: 285.2703317825862, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -573.075933, y: 285.093309, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -569.988592, y: 284.872317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -566.038931, y: 284.741812, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -561.868997, y: 284.819398, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -557.245158, y: 285.052837, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -553.389325, y: 285.274465, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -547.927148, y: 285.675653, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -543.416666, y: 286.015084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -538.09366, y: 286.422658, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -533.572691, y: 286.784704, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -521.271306, y: 286.555602, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -513.1251, y: 286.316898, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -507.576925, y: 284.968568, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -502.382312, y: 283.789355, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -498.208397, y: 282.685349, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -493.823117, y: 281.168941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -488.338555, y: 279.515963, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -484.480756, y: 278.283505, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -479.693158, y: 277.136477, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.348421, y: 275.488106, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -467.648385, y: 273.895523, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -462.782124, y: 272.702993, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -459.301545, y: 272.304816, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -453.756417, y: 271.26348, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -450.486863, y: 270.900851, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.902282, y: 270.452941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.094023, y: 269.990981, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -436.081002, y: 269.816579, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -428.723764, y: 269.647211, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -423.756517, y: 268.784376, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -420.688955, y: 270.050477, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -415.208069, y: 271.091924, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -410.23734, y: 272.567077, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -405.905944, y: 273.709102, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.962293, y: 274.964927, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -396.32977, y: 276.821343, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -393.028625, y: 278.202785, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.942984, y: 279.854199, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -384.512765, y: 281.420118, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -379.038872, y: 283.324358, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.115856, y: 285.17159, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -374.796421, y: 287.388662, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -372.38757, y: 289.569926, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -369.787663, y: 288.797859, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -369.029482, y: 286.868456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -368.6981904348235, y: 286.276039202593, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -366.266033, y: 285.933341, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -364.010266, y: 280.209593, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -361.658272, y: 275.512144, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -359.088463, y: 268.72635, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -358.374931, y: 265.329573, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -358.002303, y: 260.129191, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -357.47147, y: 256.50852, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.55101, y: 253.112803, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.153889, y: 250.200198, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -355.651569, y: 247.650533, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -354.864451, y: 244.671612, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -353.238155, y: 239.035868, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -351.894896, y: 235.519307, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -351.277427, y: 233.177347, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.946553, y: 229.801848, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.683078, y: 226.133751, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.564134, y: 223.198487, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.528974, y: 217.850372, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.440674, y: 214.431512, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -349.241184, y: 206.760217, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -348.657631, y: 201.590692, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -347.643705, y: 197.094937, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -346.265917, y: 193.221872, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -344.993631, y: 190.024301, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -342.680858, y: 187.656578, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -339.887049, y: 184.934261, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -336.803715, y: 182.414431, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -333.993515, y: 179.560741, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -330.937106, y: 177.12995, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -327.96705, y: 174.6574, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -324.396496, y: 171.420092, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -321.381022, y: 168.666823, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -318.338271, y: 165.606955, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -316.845623, y: 163.470909, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -314.497406, y: 160.53635, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.421064, y: 157.377361, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.133956, y: 153.911177, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.183707, y: 150.686645, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.04892, y: 146.247633, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.299389, y: 142.294269, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.275515, y: 137.473212, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.313543, y: 134.031663, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.484206, y: 129.982276, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.48693, y: 126.22412, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.372623, y: 122.081299, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.240626, y: 116.974682, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.27294, y: 113.786317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -312.933365, y: 110.800943, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -312.497171, y: 104.562934, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -311.49725, y: 100.006785, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -310.852109, y: 96.24905, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -311.109968, y: 92.426833, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.342563, y: 89.550152, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -317.142428, y: 87.21735, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -320.610403, y: 85.441526, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -323.501186, y: 83.909183, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -327.76901, y: 83.196064, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -333.740903, y: 82.791991, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -338.198051, y: 81.496761, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -345.410371, y: 80.023559, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -351.202614, y: 79.144775, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.482275, y: 78.561014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -360.825748, y: 78.012572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -365.227869, y: 74.315571, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -368.242375, y: 71.528417, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -371.526422, y: 68.62204, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -373.862854, y: 65.891403, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -374.640398, y: 60.789682, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -374.770627, y: 51.83419, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -371.85616274612477, y: 50.237393713239555, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -365.912902, y: 50.52362, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -360.443096, y: 51.002397, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -355.702202, y: 50.882014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.444363, y: 50.614426, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -347.362072, y: 50.445419, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -343.312114, y: 50.385851, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -339.569822, y: 50.229057, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -335.767565, y: 50.294344, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -331.627807, y: 49.844074, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -328.367714, y: 49.893125, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -324.907197, y: 49.839787, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -321.104036, y: 49.888902, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -317.59793, y: 49.984511, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -312.495078, y: 50.214162, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -308.624496, y: 50.203314, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -304.315952, y: 50.303436, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -299.628557, y: 50.490222, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -295.523471, y: 50.654075, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -292.317858, y: 50.669652, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -286.87384, y: 50.984882, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -282.841052, y: 51.035833, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -278.714567, y: 51.219971, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -272.352755, y: 51.522941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -265.691339, y: 50.989949, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -262.040402, y: 49.718833, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -258.196389, y: 46.648063, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -253.695457, y: 43.868587, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -247.537074, y: 43.570474, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500880.699932, frame_id: map} + pose: + position: {x: -247.50695196751968, y: 43.605969031972975, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.023773325930911925, w: 0.9997173745485184} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints0.yaml new file mode 100644 index 0000000..643c346 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints0.yaml @@ -0,0 +1,66 @@ +waypoints: +- point: {x: 4.09724, y: 0.504168, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 16.659, y: 1.14789, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 20.5776, y: 1.30268, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.2563, y: 1.64634, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 38.1161, y: 1.91456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.2937, y: 1.73542, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.5451, y: 1.66404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 58.0735, y: 0.128874, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 61.313, y: -6.31239, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 64.9454, y: -14.2518, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 67.6144, y: -15.4014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 70.316, y: -15.5441, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.2391, y: -15.3596, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 77.357, y: -15.2531, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 79.101358, y: -15.32212, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.470272, y: -16.227709, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 81.691765, y: -17.449202, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 83.0514, y: -18.1883, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 85.4238, y: -18.5438, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.9159, y: -17.5321, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.2617, y: -15.0813, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.16, y: -10.9362, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 88.0087, y: -6.39951, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.8094, y: -2.38376, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 87.683, y: 3.18917, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 84.1737, y: 4.69392, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 80.0329, y: 4.54753, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 74.1995, y: 2.24651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 69.9941, y: -0.0748514, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 63.1423, y: -4.43719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 59.449401, y: -7.597903, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 55.4954, y: -9.77409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 51.7554, y: -10.206, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 48.1474, y: -10.3002, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 46.051, y: -11.3614, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 42.5089, y: -11.9516, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 37.4443, y: -12.0861, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 35.2285, y: -12.1586, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.8879, y: -14.2313, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 33.7788, y: -17.3731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 32.519273, y: -19.091731, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 28.243205, y: -19.061404, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 23.785178, y: -19.00075, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 21.2425, y: -18.9706, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 19.1694, y: -19.0082, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 17.5523, y: -18.9316, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 15.426, y: -18.7627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 12.495, y: -18.5628, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 10.0156, y: -18.6638, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 7.32172, y: -18.6572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 6.06788, y: -21.9222, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 5.40629, y: -26.6174, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: 0.550092, y: -27.6913, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -5.94073, y: -28.0941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -10.5427, y: -28.3094, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -16.6638, y: -28.2209, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -23.255, y: -28.019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -34.563433, y: -33.284636, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -43.9865, y: -35.5365, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -49.5035, y: -37.0547, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666489211.5504568, frame_id: map} + pose: + position: {x: -59.2588, y: -38.328, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.99999541274693, w: 0.00302894125019187} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints1.yaml new file mode 100644 index 0000000..61b4952 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints1.yaml @@ -0,0 +1,52 @@ +waypoints: +- point: {x: -65.997293, y: -37.687546, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -74.861316, y: -36.722816, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -78.968532, y: -36.718417, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -83.75627, y: -36.856869, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -88.925109, y: -36.80009, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -98.145582, y: -36.858084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -105.729932, y: -37.112591, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -112.827094, y: -37.178238, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -119.614722, y: -36.806496, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -125.185643, y: -37.034113, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -136.390826, y: -39.014177, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -142.776059, y: -38.943692, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -151.30381, y: -38.555669, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -156.31217, y: -38.560155, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -163.008984, y: -38.679659, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -170.633876, y: -38.925466, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -178.163055, y: -39.056873, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -186.167354, y: -39.218148, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -192.194294, y: -37.156126, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -199.637462, y: -37.243308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -206.68365, y: -37.172295, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -213.963337, y: -36.947721, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -219.989733, y: -36.657375, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -225.740345, y: -39.515697, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.145509, y: -33.082141, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -230.035577, y: -28.839193, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.883482, y: -23.875298, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.837519, y: -15.687723, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.753517, y: -7.754537, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.822194, y: -2.821888, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.724764, y: 1.391393, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.687153, y: 7.635213, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.532438, y: 11.101565, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.571416, y: 15.277872, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.641011, y: 22.795954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.608802, y: 26.524621, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.84853, y: 32.493456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.567279, y: 34.716681, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.672466, y: 37.262953, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.796547, y: 39.658066, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.198126, y: 41.696698, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.193767, y: 43.152423, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -233.670353, y: 45.568782, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -247.758964, y: 45.75834, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.321939, y: 42.876876, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.797814, y: 32.789915, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666494610.9868476, frame_id: map} + pose: + position: {x: -253.5219939015618, y: 32.55980001412175, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9978975125513841, w: 0.06481168446939334} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints2.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints2.yaml new file mode 100644 index 0000000..11e34e2 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints2.yaml @@ -0,0 +1,89 @@ +waypoints: +- point: {x: -258.053394, y: 29.890619, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -264.168789, y: 29.17392, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -270.693645, y: 28.611301, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -277.691194, y: 28.668496, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -283.610716, y: 28.529514, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -288.410126, y: 28.1954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -291.940999, y: 28.013434, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -299.442501, y: 27.529333, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -304.259884, y: 27.396202, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -311.681235, y: 26.983278, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -317.613147, y: 26.511184, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -319.976311, y: 26.535241, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -326.660905, y: 26.111805, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -332.427465, y: 25.81337, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -336.962273, y: 28.125288, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -344.737269, y: 28.01525, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -349.460252, y: 27.871153, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.480806, y: 27.908136, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -362.737053, y: 27.714504, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -372.583986, y: 27.593499, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -378.874107, y: 26.967331, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -382.138561, y: 26.787573, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -393.261261, y: 25.868445, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.538061, y: 25.44106, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -407.076689, y: 25.207773, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -415.964264, y: 24.658856, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -419.724021, y: 24.418726, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -424.37104, y: 24.352715, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -434.608025, y: 23.505254, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -442.741447, y: 22.684765, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -450.938911, y: 22.513319, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -458.383171, y: 22.127258, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -464.87087, y: 21.984709, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -468.132469, y: 21.626119, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -471.323492, y: 21.55016, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.336647, y: 21.889659, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -477.32265, y: 21.631686, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -481.47698, y: 21.16945, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -486.159348, y: 20.094339, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -490.825029, y: 19.257699, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -495.633463, y: 19.876072, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -500.004502, y: 19.663624, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -505.576354, y: 19.511281, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -510.23767, y: 18.403005, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -513.243141, y: 17.497047, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -518.04732, y: 17.25395, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -522.318997, y: 18.216145, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.181251, y: 21.720748, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.220418, y: 26.772257, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.730054, y: 31.445867, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.787967, y: 35.524397, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.605593, y: 40.106628, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -523.145867, y: 42.598064, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -522.391933, y: 43.761488, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -518.116883, y: 44.938371, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -512.948437, y: 45.116464, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -506.716044, y: 43.861395, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -500.243992, y: 46.981211, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -493.962431, y: 47.201147, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -488.787598, y: 47.437265, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -482.293905, y: 47.603487, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -475.602806, y: 47.550518, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -468.045147, y: 47.973646, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -462.835636, y: 48.192481, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -456.502336, y: 48.500156, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -451.722115, y: 48.901493, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.717969, y: 48.654826, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.602746, y: 48.754387, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -438.877463, y: 48.517506, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -432.316376, y: 49.179618, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -426.472211, y: 49.544632, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -419.409104, y: 50.203781, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -414.692869, y: 50.466941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -410.344484, y: 50.498807, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -405.509605, y: 50.725226, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -399.29213, y: 50.99345, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -395.811454, y: 50.947499, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -391.480197, y: 51.048554, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.324064, y: 51.224959, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -383.675982, y: 50.912722, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.836947, y: 49.929266, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -377.70745, y: 52.005824, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -377.105479, y: 60.481631, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666496150.059658, frame_id: map} + pose: + position: {x: -376.2159677819452, y: 67.59687010838871, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6407727364090109, w: 0.7677306169972045} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints3.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints3.yaml new file mode 100644 index 0000000..a51e8ff --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints3.yaml @@ -0,0 +1,64 @@ +waypoints: +- point: {x: -375.996853, y: 71.58048, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.816357, y: 74.785425, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.776873, y: 79.972962, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.784127, y: 83.324964, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.948441, y: 87.238649, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.878229, y: 93.223836, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.75997, y: 100.252255, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.124383, y: 104.698424, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.183786, y: 109.935906, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.966584, y: 115.373864, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.046354, y: 118.958734, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.041771, y: 123.005498, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.714012, y: 128.267064, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.761426, y: 131.831983, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.889254, y: 134.273015, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -379.594506, y: 135.135863, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -384.304822, y: 134.561862, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.666492, y: 135.025177, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -392.6819, y: 134.322875, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -396.752025, y: 134.188627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -400.273072, y: 134.798615, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -404.957435, y: 134.349375, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -404.544916, y: 133.998821, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -409.164332, y: 133.857758, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -413.239594, y: 133.695817, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -416.906021, y: 133.46068, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -420.123743, y: 133.306324, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -426.270839, y: 133.578248, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -430.975705, y: 133.686245, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -437.040996, y: 133.57616, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.115877, y: 133.507738, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -443.508932, y: 133.334966, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -445.877453, y: 133.559804, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -450.496813, y: 133.656158, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -455.38663, y: 133.768045, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -460.454056, y: 133.458128, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -471.108747, y: 133.712433, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.453845, y: 133.777743, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -480.076059, y: 133.413976, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -483.066964, y: 133.308488, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -488.377362, y: 133.33122, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -491.634572, y: 133.459615, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -495.195347, y: 133.423018, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -498.54888, y: 133.45007, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -501.899703, y: 134.280135, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -506.267554, y: 134.827364, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -511.337918, y: 133.557358, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -515.911679, y: 133.469308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -520.426659, y: 135.057578, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -524.680573, y: 135.221091, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -536.04867, y: 135.811884, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -547.472381, y: 135.240112, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -550.969299, y: 135.083822, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -560.372569, y: 134.952614, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -566.098996, y: 135.102915, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -571.366929, y: 133.532739, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -578.328994, y: 133.710034, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -584.532392, y: 135.903225, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666497569.7515693, frame_id: map} + pose: + position: {x: -588.113016943929, y: 138.6890288736552, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6952399520376623, w: 0.718777718832929} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints4.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints4.yaml new file mode 100644 index 0000000..03dc0b7 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints4.yaml @@ -0,0 +1,37 @@ +waypoints: +- point: {x: -588.331708, y: 143.57969, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -588.1925, y: 151.281553, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -587.8078, y: 156.198734, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -587.546379, y: 159.623015, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -587.369936, y: 163.207274, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.917233, y: 167.0085, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.292124, y: 171.255572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.889245, y: 176.106561, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.566909, y: 179.992549, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.570464, y: 184.540065, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.748241, y: 188.41317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.184276, y: 195.07826, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.280951, y: 199.935042, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.517487, y: 206.929981, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.401481, y: 210.598052, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.140378, y: 215.167657, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -586.057455, y: 219.181678, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.502373, y: 222.531465, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -585.164629, y: 225.964978, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -584.347585, y: 230.585385, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.606556, y: 234.611835, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.474776, y: 239.329366, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.438094, y: 243.883497, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.091327, y: 249.375227, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.557588, y: 254.336429, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.623731, y: 259.121231, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.964634, y: 264.439564, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.422049, y: 269.12651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.755804, y: 272.414019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -583.940492, y: 277.146227, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -580.627806, y: 283.714641, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666498137.866959, frame_id: map} + pose: + position: {x: -576.0559809514564, y: 285.2703317825862, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9986561204160153, w: 0.051826182144097996} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints5.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints5.yaml new file mode 100644 index 0000000..83781e5 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints5.yaml @@ -0,0 +1,51 @@ +waypoints: +- point: {x: -573.075933, y: 285.093309, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -569.988592, y: 284.872317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -566.038931, y: 284.741812, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -561.868997, y: 284.819398, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -557.245158, y: 285.052837, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -553.389325, y: 285.274465, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -547.927148, y: 285.675653, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -543.416666, y: 286.015084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -538.09366, y: 286.422658, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -533.572691, y: 286.784704, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -521.271306, y: 286.555602, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -513.1251, y: 286.316898, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -507.576925, y: 284.968568, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -502.382312, y: 283.789355, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -498.208397, y: 282.685349, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -493.823117, y: 281.168941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -488.338555, y: 279.515963, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -484.480756, y: 278.283505, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -479.693158, y: 277.136477, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.348421, y: 275.488106, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -467.648385, y: 273.895523, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -462.782124, y: 272.702993, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -459.301545, y: 272.304816, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -453.756417, y: 271.26348, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -450.486863, y: 270.900851, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.902282, y: 270.452941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.094023, y: 269.990981, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -436.081002, y: 269.816579, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -428.723764, y: 269.647211, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -423.756517, y: 268.784376, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -420.688955, y: 270.050477, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -415.208069, y: 271.091924, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -410.23734, y: 272.567077, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -405.905944, y: 273.709102, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.962293, y: 274.964927, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -396.32977, y: 276.821343, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -393.028625, y: 278.202785, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.942984, y: 279.854199, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -384.512765, y: 281.420118, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -379.038872, y: 283.324358, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -376.115856, y: 285.17159, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -374.796421, y: 287.388662, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -372.38757, y: 289.569926, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -369.787663, y: 288.797859, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -369.029482, y: 286.868456, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666498996.6713529, frame_id: map} + pose: + position: {x: -368.6981904348235, y: 286.276039202593, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6497142633806916, w: 0.7601785158498531} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints6.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints6.yaml new file mode 100644 index 0000000..95d81e4 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints6.yaml @@ -0,0 +1,75 @@ +waypoints: +- point: {x: -366.266033, y: 285.933341, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -364.010266, y: 280.209593, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -361.658272, y: 275.512144, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -359.088463, y: 268.72635, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -358.374931, y: 265.329573, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -358.002303, y: 260.129191, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -357.47147, y: 256.50852, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.55101, y: 253.112803, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.153889, y: 250.200198, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -355.651569, y: 247.650533, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -354.864451, y: 244.671612, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -353.238155, y: 239.035868, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -351.894896, y: 235.519307, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -351.277427, y: 233.177347, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.946553, y: 229.801848, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.683078, y: 226.133751, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.564134, y: 223.198487, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.528974, y: 217.850372, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.440674, y: 214.431512, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -349.241184, y: 206.760217, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -348.657631, y: 201.590692, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -347.643705, y: 197.094937, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -346.265917, y: 193.221872, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -344.993631, y: 190.024301, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -342.680858, y: 187.656578, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -339.887049, y: 184.934261, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -336.803715, y: 182.414431, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -333.993515, y: 179.560741, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -330.937106, y: 177.12995, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -327.96705, y: 174.6574, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -324.396496, y: 171.420092, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -321.381022, y: 168.666823, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -318.338271, y: 165.606955, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -316.845623, y: 163.470909, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -314.497406, y: 160.53635, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.421064, y: 157.377361, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.133956, y: 153.911177, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.183707, y: 150.686645, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.04892, y: 146.247633, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.299389, y: 142.294269, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.275515, y: 137.473212, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.313543, y: 134.031663, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.484206, y: 129.982276, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.48693, y: 126.22412, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.372623, y: 122.081299, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.240626, y: 116.974682, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.27294, y: 113.786317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -312.933365, y: 110.800943, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -312.497171, y: 104.562934, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -311.49725, y: 100.006785, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -310.852109, y: 96.24905, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -311.109968, y: 92.426833, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -313.342563, y: 89.550152, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -317.142428, y: 87.21735, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -320.610403, y: 85.441526, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -323.501186, y: 83.909183, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -327.76901, y: 83.196064, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -333.740903, y: 82.791991, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -338.198051, y: 81.496761, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -345.410371, y: 80.023559, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -351.202614, y: 79.144775, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -356.482275, y: 78.561014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -360.825748, y: 78.012572, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -365.227869, y: 74.315571, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -368.242375, y: 71.528417, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -371.526422, y: 68.62204, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -373.862854, y: 65.891403, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -374.640398, y: 60.789682, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -374.770627, y: 51.83419, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500443.4820855, frame_id: map} + pose: + position: {x: -371.85616274612477, y: 50.237393713239555, z: 0} + orientation: {x: -0.0, y: 0.0, z: -0.03354948946468183, w: 0.9994370574261588} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints7.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints7.yaml new file mode 100644 index 0000000..c4201ea --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba/waypoints7.yaml @@ -0,0 +1,34 @@ +waypoints: +- point: {x: -365.912902, y: 50.52362, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -360.443096, y: 51.002397, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -355.702202, y: 50.882014, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -350.444363, y: 50.614426, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -347.362072, y: 50.445419, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -343.312114, y: 50.385851, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -339.569822, y: 50.229057, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -335.767565, y: 50.294344, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -331.627807, y: 49.844074, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -328.367714, y: 49.893125, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -324.907197, y: 49.839787, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -321.104036, y: 49.888902, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -317.59793, y: 49.984511, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -312.495078, y: 50.214162, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -308.624496, y: 50.203314, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -304.315952, y: 50.303436, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -299.628557, y: 50.490222, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -295.523471, y: 50.654075, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -292.317858, y: 50.669652, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -286.87384, y: 50.984882, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -282.841052, y: 51.035833, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -278.714567, y: 51.219971, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -272.352755, y: 51.522941, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -265.691339, y: 50.989949, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -262.040402, y: 49.718833, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -258.196389, y: 46.648063, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -253.695457, y: 43.868587, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -247.537074, y: 43.570474, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500880.699932, frame_id: map} + pose: + position: {x: -247.50695196751968, y: 43.605969031972975, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.023773325930911925, w: 0.9997173745485184} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/map0.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map0.pgm new file mode 100644 index 0000000..73e0ac3 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map0.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/map0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map0.yaml new file mode 100644 index 0000000..9b76850 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map0.yaml @@ -0,0 +1,6 @@ +image: ./map0.pgm +resolution: 0.1 +origin: [-143.81257306980442, -82.64700016075858, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/map1.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map1.pgm new file mode 100644 index 0000000..9ada042 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map1.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/map1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map1.yaml new file mode 100644 index 0000000..1aeb63f --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/map1.yaml @@ -0,0 +1,6 @@ +image: ./map1.pgm +resolution: 0.1 +origin: [-288.393131, -87.22861, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/mymap_tsukuba_2_rect.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_2/mymap_tsukuba_2_rect.pgm new file mode 100644 index 0000000..06cbc76 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/mymap_tsukuba_2_rect.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/mymap_tsukuba_2_rect.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_2/mymap_tsukuba_2_rect.yaml new file mode 100644 index 0000000..3c7203e --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/mymap_tsukuba_2_rect.yaml @@ -0,0 +1,6 @@ +image: ./mymap_tsukuba_2_rect.pgm +resolution: 0.1 +origin: [-288.3931311734531, -87.22861015928352, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints0.yaml new file mode 100644 index 0000000..da0f96f --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints0.yaml @@ -0,0 +1,17 @@ +waypoints: +- point: {x: -65.997293, y: -37.687546, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -74.861316, y: -36.722816, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -78.968532, y: -36.718417, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -83.75627, y: -36.856869, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -88.925109, y: -36.80009, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -98.145582, y: -36.858084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -105.729932, y: -37.112591, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -112.827094, y: -37.178238, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -119.614722, y: -36.806496, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -125.185643, y: -37.034113, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -136.390826, y: -39.014177, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666494610.9868476, frame_id: map} + pose: + position: {x: -142.776059, y: -38.943692, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9995130260489076, w: 0.031204338777736002} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints1.yaml new file mode 100644 index 0000000..3be7448 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints1.yaml @@ -0,0 +1,40 @@ +waypoints: +- point: {x: -151.30381, y: -38.555669, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -156.31217, y: -38.560155, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -163.008984, y: -38.679659, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -170.633876, y: -38.925466, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -178.163055, y: -39.056873, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -186.167354, y: -39.218148, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -192.194294, y: -37.156126, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -199.637462, y: -37.243308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -206.68365, y: -37.172295, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -213.963337, y: -36.947721, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -219.989733, y: -36.657375, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -225.740345, y: -39.515697, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.145509, y: -33.082141, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -230.035577, y: -28.839193, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.883482, y: -23.875298, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.837519, y: -15.687723, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.753517, y: -7.754537, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.822194, y: -2.821888, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.724764, y: 1.391393, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.687153, y: 7.635213, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.532438, y: 11.101565, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.571416, y: 15.277872, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.641011, y: 22.795954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.608802, y: 26.524621, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.84853, y: 32.493456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.567279, y: 34.716681, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.672466, y: 37.262953, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.796547, y: 39.658066, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.198126, y: 41.696698, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.193767, y: 43.152423, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -233.670353, y: 45.568782, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -247.758964, y: 45.75834, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.321939, y: 42.876876, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.797814, y: 32.789915, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666494610.9868476, frame_id: map} + pose: + position: {x: -253.5219939015618, y: 32.55980001412175, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9978975125513841, w: 0.06481168446939334} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints_tsukuba_2.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints_tsukuba_2.yaml new file mode 100644 index 0000000..60ad550 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_2/waypoints_tsukuba_2.yaml @@ -0,0 +1,52 @@ +waypoints: +- point: {x: -65.997293, y: -37.687546, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -74.861316, y: -36.722816, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -78.968532, y: -36.718417, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -83.75627, y: -36.856869, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -88.925109, y: -36.80009, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -98.145582, y: -36.858084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -105.729932, y: -37.112591, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -112.827094, y: -37.178238, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -119.614722, y: -36.806496, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -125.185643, y: -37.034113, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -136.390826, y: -39.014177, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -142.776059, y: -38.943692, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -151.30381, y: -38.555669, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -156.31217, y: -38.560155, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -163.008984, y: -38.679659, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -170.633876, y: -38.925466, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -178.163055, y: -39.056873, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -186.167354, y: -39.218148, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -192.194294, y: -37.156126, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -199.637462, y: -37.243308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -206.68365, y: -37.172295, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -213.963337, y: -36.947721, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -219.989733, y: -36.657375, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -225.740345, y: -39.515697, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.145509, y: -33.082141, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -230.035577, y: -28.839193, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.883482, y: -23.875298, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.837519, y: -15.687723, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.753517, y: -7.754537, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.822194, y: -2.821888, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.724764, y: 1.391393, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.687153, y: 7.635213, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.532438, y: 11.101565, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.571416, y: 15.277872, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.641011, y: 22.795954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.608802, y: 26.524621, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -229.84853, y: 32.493456, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.567279, y: 34.716681, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.672466, y: 37.262953, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -231.796547, y: 39.658066, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.198126, y: 41.696698, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -232.193767, y: 43.152423, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -233.670353, y: 45.568782, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -247.758964, y: 45.75834, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.321939, y: 42.876876, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -250.797814, y: 32.789915, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666494610.9868476, frame_id: map} + pose: + position: {x: -253.5219939015618, y: 32.55980001412175, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9978975125513841, w: 0.06481168446939334} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/map0.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map0.pgm new file mode 100644 index 0000000..310a554 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map0.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/map0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map0.yaml new file mode 100644 index 0000000..474ea4a --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map0.yaml @@ -0,0 +1,6 @@ +image: ./map0.pgm +resolution: 0.1 +origin: [-324.65831122520103, -15.237809571939238, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/map1.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map1.pgm new file mode 100644 index 0000000..b4194c2 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map1.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/map1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map1.yaml new file mode 100644 index 0000000..a92aa98 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map1.yaml @@ -0,0 +1,6 @@ +image: ./map1.pgm +resolution: 0.1 +origin: [-550.664972, -29.044655, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/map2.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map2.pgm new file mode 100644 index 0000000..8b496ef --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map2.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/map2.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map2.yaml new file mode 100644 index 0000000..1d8ba4d --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/map2.yaml @@ -0,0 +1,6 @@ +image: ./map2.pgm +resolution: 0.1 +origin: [-550.331199, 30.543284, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/mymap_tsukuba_3_rect.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_3/mymap_tsukuba_3_rect.pgm new file mode 100644 index 0000000..9811ff0 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/mymap_tsukuba_3_rect.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/mymap_tsukuba_3_rect.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/mymap_tsukuba_3_rect.yaml new file mode 100644 index 0000000..b19c837 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/mymap_tsukuba_3_rect.yaml @@ -0,0 +1,6 @@ +image: ./mymap_tsukuba_3_rect.pgm +resolution: 0.1 +origin: [-550.6649715593369, -29.044654528977503, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints0.yaml new file mode 100644 index 0000000..1e21803 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints0.yaml @@ -0,0 +1,17 @@ +waypoints: +- point: {x: -261.084644, y: 25.106299, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -267.210686, y: 24.487174, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -273.743682, y: 24.028638, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -280.73943, y: 24.197371, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -286.660415, y: 24.152768, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -291.464542, y: 23.895203, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -294.997867, y: 23.769544, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -302.506132, y: 23.405084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -307.325026, y: 23.348762, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -314.752016, y: 23.054192, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -320.6907, y: 22.676717, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666496150.059658, frame_id: map} + pose: + position: {x: -323.05318, y: 22.738441, z: 0} + orientation: {x: 0.0, y: 0.0, z: 1.0, w: 6.123233995736766e-17} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints1.yaml new file mode 100644 index 0000000..99a7b41 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints1.yaml @@ -0,0 +1,46 @@ +waypoints: +- point: {x: -329.743674, y: 22.421616, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -335.514259, y: 22.215142, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -340.011637, y: 24.599054, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -347.787399, y: 24.612969, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -352.512079, y: 24.544178, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -359.531152, y: 24.693069, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -365.78969, y: 24.599191, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.637301, y: 24.635168, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -381.936604, y: 24.109348, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -385.203509, y: 23.981651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -396.339447, y: 23.239943, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -404.622009, y: 22.94455, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -410.163652, y: 22.799583, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -419.058847, y: 22.392409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -422.821955, y: 22.212243, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -427.469435, y: 22.220317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -437.718629, y: 21.536149, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.864096, y: 20.845416, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -454.063252, y: 20.804665, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -461.51272, y: 20.53732, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -468.001867, y: 20.498208, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -471.268768, y: 20.191655, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.460596, y: 20.166573, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -477.467957, y: 20.554061, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -480.457692, y: 20.343719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -484.618863, y: 19.947765, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -489.317774, y: 18.947431, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -493.996199, y: 18.185271, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -498.794164, y: 18.880216, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -503.168035, y: 18.737472, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -508.741607, y: 18.673968, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -513.419998, y: 17.640137, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -516.439528, y: 16.782203, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -521.246972, y: 16.615719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -525.502768, y: 17.645885, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.309047, y: 21.163788, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.267684, y: 26.21528, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.702755, y: 30.89642, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.695646, y: 34.975355, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.440251, y: 39.554096, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666496150.059658, frame_id: map} + pose: + position: {x: -525.9408683028532, y: 42.03788778419087, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6963984346067804, w: 0.7176553631634238} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints2.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints2.yaml new file mode 100644 index 0000000..162c0f4 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints2.yaml @@ -0,0 +1,36 @@ +waypoints: +- point: {x: -525.168484, y: 43.189145, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -520.875217, y: 44.297732, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -515.704589, y: 44.393413, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -509.492995, y: 43.039155, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -502.972033, y: 46.055406, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -496.687764, y: 46.175181, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -491.509825, y: 46.328779, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -485.014307, y: 46.391466, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -478.324903, y: 46.231843, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -470.761459, y: 46.534443, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -465.549122, y: 46.670207, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -459.211722, y: 46.876885, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -454.425711, y: 47.201971, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -448.426259, y: 46.859625, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -444.309972, y: 46.893574, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.588812, y: 46.61328, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -435.018004, y: 47.17072, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -429.168763, y: 47.442527, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -422.096046, y: 47.989002, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -417.376215, y: 48.176948, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -413.027875, y: 48.139494, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -408.190001, y: 48.288813, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.96904, y: 48.457892, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -398.489539, y: 48.356462, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -394.157221, y: 48.388461, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -390.998677, y: 48.514533, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -386.356163, y: 48.128242, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -383.533166, y: 47.099655, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.370965, y: 49.126063, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -379.63396, y: 57.591197, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666496150.059658, frame_id: map} + pose: + position: {x: -378.63113989298256, y: 64.69135239689587, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6346331075746171, w: 0.7728135731016792} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints_tsukuba_3.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints_tsukuba_3.yaml new file mode 100644 index 0000000..4de40e7 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_3/waypoints_tsukuba_3.yaml @@ -0,0 +1,89 @@ +waypoints: +- point: {x: -261.084644, y: 25.106299, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -267.210686, y: 24.487174, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -273.743682, y: 24.028638, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -280.73943, y: 24.197371, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -286.660415, y: 24.152768, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -291.464542, y: 23.895203, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -294.997867, y: 23.769544, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -302.506132, y: 23.405084, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -307.325026, y: 23.348762, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -314.752016, y: 23.054192, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -320.6907, y: 22.676717, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -323.05318, y: 22.738441, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -329.743674, y: 22.421616, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -335.514259, y: 22.215142, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -340.011637, y: 24.599054, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -347.787399, y: 24.612969, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -352.512079, y: 24.544178, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -359.531152, y: 24.693069, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -365.78969, y: 24.599191, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -375.637301, y: 24.635168, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -381.936604, y: 24.109348, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -385.203509, y: 23.981651, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -396.339447, y: 23.239943, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -404.622009, y: 22.94455, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -410.163652, y: 22.799583, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -419.058847, y: 22.392409, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -422.821955, y: 22.212243, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -427.469435, y: 22.220317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -437.718629, y: 21.536149, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.864096, y: 20.845416, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -454.063252, y: 20.804665, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -461.51272, y: 20.53732, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -468.001867, y: 20.498208, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -471.268768, y: 20.191655, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -474.460596, y: 20.166573, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -477.467957, y: 20.554061, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -480.457692, y: 20.343719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -484.618863, y: 19.947765, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -489.317774, y: 18.947431, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -493.996199, y: 18.185271, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -498.794164, y: 18.880216, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -503.168035, y: 18.737472, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -508.741607, y: 18.673968, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -513.419998, y: 17.640137, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -516.439528, y: 16.782203, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -521.246972, y: 16.615719, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -525.502768, y: 17.645885, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.309047, y: 21.163788, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.267684, y: 26.21528, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.702755, y: 30.89642, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.695646, y: 34.975355, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -526.440251, y: 39.554096, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -525.9408683028532, y: 42.03788778419087, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -525.168484, y: 43.189145, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -520.875217, y: 44.297732, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -515.704589, y: 44.393413, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -509.492995, y: 43.039155, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -502.972033, y: 46.055406, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -496.687764, y: 46.175181, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -491.509825, y: 46.328779, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -485.014307, y: 46.391466, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -478.324903, y: 46.231843, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -470.761459, y: 46.534443, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -465.549122, y: 46.670207, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -459.211722, y: 46.876885, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -454.425711, y: 47.201971, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -448.426259, y: 46.859625, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -444.309972, y: 46.893574, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.588812, y: 46.61328, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -435.018004, y: 47.17072, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -429.168763, y: 47.442527, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -422.096046, y: 47.989002, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -417.376215, y: 48.176948, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -413.027875, y: 48.139494, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -408.190001, y: 48.288813, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.96904, y: 48.457892, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -398.489539, y: 48.356462, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -394.157221, y: 48.388461, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -390.998677, y: 48.514533, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -386.356163, y: 48.128242, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -383.533166, y: 47.099655, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.370965, y: 49.126063, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -379.63396, y: 57.591197, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666496150.059658, frame_id: map} + pose: + position: {x: -378.63113989298256, y: 64.69135239689587, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6346331075746171, w: 0.7728135731016792} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/map0.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map0.pgm new file mode 100644 index 0000000..f65804f --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map0.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/map0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map0.yaml new file mode 100644 index 0000000..6922558 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map0.yaml @@ -0,0 +1,6 @@ +image: ./map0.pgm +resolution: 0.1 +origin: [-411.71522742895434, 58.956719886505816, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/map1.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map1.pgm new file mode 100644 index 0000000..65347b1 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map1.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/map1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map1.yaml new file mode 100644 index 0000000..a25d744 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map1.yaml @@ -0,0 +1,6 @@ +image: ./map1.pgm +resolution: 0.1 +origin: [-449.340049, 128.403487, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/map2.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map2.pgm new file mode 100644 index 0000000..444bbaf --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map2.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/map2.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map2.yaml new file mode 100644 index 0000000..f7570f0 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/map2.yaml @@ -0,0 +1,6 @@ +image: ./map2.pgm +resolution: 0.1 +origin: [-606.555774, 117.492454, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/mymap_tsukuba_4_rect.pgm b/src/tsukuba2022/multimaps/tmp/tsukuba_4/mymap_tsukuba_4_rect.pgm new file mode 100644 index 0000000..9aca87b --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/mymap_tsukuba_4_rect.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/mymap_tsukuba_4_rect.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/mymap_tsukuba_4_rect.yaml new file mode 100644 index 0000000..6dd4beb --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/mymap_tsukuba_4_rect.yaml @@ -0,0 +1,6 @@ +image: ./mymap_tsukuba_4_rect.pgm +resolution: 0.1 +origin: [-606.5557738478564, 58.956719886505816, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints0.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints0.yaml new file mode 100644 index 0000000..3881b53 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints0.yaml @@ -0,0 +1,27 @@ +waypoints: +- point: {x: -380.394722, y: 71.704364, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.214226, y: 74.909309, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.174742, y: 80.096846, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.181996, y: 83.448848, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.34631, y: 87.362533, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.276098, y: 93.34772, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.157839, y: 100.376139, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.522252, y: 104.822308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.581655, y: 110.05979, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.364453, y: 115.497748, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.444223, y: 119.082618, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.43964, y: 123.129382, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.111881, y: 128.390948, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.159295, y: 131.955867, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -381.287123, y: 134.396899, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -383.992375, y: 135.259747, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.702691, y: 134.685746, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -393.064361, y: 135.149061, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -397.079769, y: 134.446759, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.149894, y: 134.312511, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -404.670941, y: 134.922499, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666497569.7515693, frame_id: map} + pose: + position: {x: -409.355304, y: 134.473259, z: 0} + orientation: {x: 0.0, y: 0.0, z: 1.0, w: 6.123233995736766e-17} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints1.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints1.yaml new file mode 100644 index 0000000..cd28e84 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints1.yaml @@ -0,0 +1,15 @@ +waypoints: +- point: {x: -408.942785, y: 134.122705, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -413.562201, y: 133.981642, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -417.637463, y: 133.819701, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -421.30389, y: 133.584564, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -424.521612, y: 133.430208, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -430.668708, y: 133.702132, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -435.373574, y: 133.810129, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.438865, y: 133.700044, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.513746, y: 133.631622, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666497569.7515693, frame_id: map} + pose: + position: {x: -447.90680120213875, y: 133.45884979262743, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.9992669478249188, w: 0.03828272436323098} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints2.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints2.yaml new file mode 100644 index 0000000..0b49634 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints2.yaml @@ -0,0 +1,32 @@ +waypoints: +- point: {x: -450.275322, y: 133.683688, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -454.894682, y: 133.780042, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -459.784499, y: 133.891929, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -464.851925, y: 133.582012, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -475.506616, y: 133.836317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -478.851714, y: 133.901627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -484.473928, y: 133.53786, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -487.464833, y: 133.432372, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -492.775231, y: 133.455104, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -496.032441, y: 133.583499, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -499.593216, y: 133.546902, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -502.946749, y: 133.573954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -506.297572, y: 134.404019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -510.665423, y: 134.951248, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -515.735787, y: 133.681242, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -520.309548, y: 133.593192, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -524.824528, y: 135.181462, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -529.078442, y: 135.344975, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -540.446539, y: 135.935768, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -551.87025, y: 135.363996, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -555.367168, y: 135.207706, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -564.770438, y: 135.076498, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -570.496865, y: 135.226799, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -575.764798, y: 133.656623, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.726863, y: 133.833918, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -588.930261, y: 136.027109, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666497569.7515693, frame_id: map} + pose: + position: {x: -592.510885943929, y: 138.8129128736552, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6952399520376622, w: 0.718777718832929} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints_tsukuba_4.yaml b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints_tsukuba_4.yaml new file mode 100644 index 0000000..d8d0df5 --- /dev/null +++ b/src/tsukuba2022/multimaps/tmp/tsukuba_4/waypoints_tsukuba_4.yaml @@ -0,0 +1,64 @@ +waypoints: +- point: {x: -380.394722, y: 71.704364, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.214226, y: 74.909309, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.174742, y: 80.096846, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.181996, y: 83.448848, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.34631, y: 87.362533, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.276098, y: 93.34772, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.157839, y: 100.376139, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.522252, y: 104.822308, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.581655, y: 110.05979, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.364453, y: 115.497748, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.444223, y: 119.082618, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.43964, y: 123.129382, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.111881, y: 128.390948, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -380.159295, y: 131.955867, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -381.287123, y: 134.396899, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -383.992375, y: 135.259747, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -388.702691, y: 134.685746, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -393.064361, y: 135.149061, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -397.079769, y: 134.446759, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -401.149894, y: 134.312511, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -404.670941, y: 134.922499, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -409.355304, y: 134.473259, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -408.942785, y: 134.122705, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -413.562201, y: 133.981642, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -417.637463, y: 133.819701, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -421.30389, y: 133.584564, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -424.521612, y: 133.430208, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -430.668708, y: 133.702132, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -435.373574, y: 133.810129, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -441.438865, y: 133.700044, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -445.513746, y: 133.631622, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -447.90680120213875, y: 133.45884979262743, z: 0, vel: 1, rad: 0.8, stop: true, change_map: true} +- point: {x: -450.275322, y: 133.683688, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -454.894682, y: 133.780042, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -459.784499, y: 133.891929, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -464.851925, y: 133.582012, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -475.506616, y: 133.836317, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -478.851714, y: 133.901627, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -484.473928, y: 133.53786, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -487.464833, y: 133.432372, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -492.775231, y: 133.455104, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -496.032441, y: 133.583499, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -499.593216, y: 133.546902, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -502.946749, y: 133.573954, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -506.297572, y: 134.404019, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -510.665423, y: 134.951248, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -515.735787, y: 133.681242, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -520.309548, y: 133.593192, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -524.824528, y: 135.181462, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -529.078442, y: 135.344975, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -540.446539, y: 135.935768, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -551.87025, y: 135.363996, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -555.367168, y: 135.207706, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -564.770438, y: 135.076498, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -570.496865, y: 135.226799, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -575.764798, y: 133.656623, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -582.726863, y: 133.833918, z: 0, vel: 1, rad: 0.8, stop: false} +- point: {x: -588.930261, y: 136.027109, z: 0, vel: 1, rad: 0.8, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666497569.7515693, frame_id: map} + pose: + position: {x: -592.510885943929, y: 138.8129128736552, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.6952399520376622, w: 0.718777718832929} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map0.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map0.pgm new file mode 100644 index 0000000..63f643f --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map0.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map0.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map0.yaml new file mode 100644 index 0000000..959583b --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map0.yaml @@ -0,0 +1,6 @@ +image: ./map0.pgm +resolution: 0.1 +origin: [-110.8, -78.8, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map1.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map1.pgm new file mode 100644 index 0000000..3c21440 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map1.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map1.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map1.yaml new file mode 100644 index 0000000..f830a0d --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map1.yaml @@ -0,0 +1,6 @@ +image: ./map1.pgm +resolution: 0.1 +origin: [-289.418172, -89.185045, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map2.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map2.pgm new file mode 100644 index 0000000..79011fe --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map2.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map2.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map2.yaml new file mode 100644 index 0000000..f4a5d1e --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map2.yaml @@ -0,0 +1,6 @@ +image: ./map2.pgm +resolution: 0.1 +origin: [-554.423675, -49.010222, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map3.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map3.pgm new file mode 100644 index 0000000..5619bcd --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map3.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map3.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map3.yaml new file mode 100644 index 0000000..346d9d5 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map3.yaml @@ -0,0 +1,6 @@ +image: ./map3.pgm +resolution: 0.1 +origin: [-604.640432, 48.633033, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map4.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map4.pgm new file mode 100644 index 0000000..625cb4c --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map4.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map4.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map4.yaml new file mode 100644 index 0000000..097a009 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map4.yaml @@ -0,0 +1,6 @@ +image: ./map4.pgm +resolution: 0.1 +origin: [-655.682101, 71.05415, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map5.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map5.pgm new file mode 100644 index 0000000..76a3c45 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map5.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map5.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map5.yaml new file mode 100644 index 0000000..2fa87f6 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map5.yaml @@ -0,0 +1,6 @@ +image: ./map5.pgm +resolution: 0.1 +origin: [-651.467145, 225.574369, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map6.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map6.pgm new file mode 100644 index 0000000..474bcd7 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map6.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map6.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map6.yaml new file mode 100644 index 0000000..f4db5ba --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map6.yaml @@ -0,0 +1,6 @@ +image: ./map6.pgm +resolution: 0.1 +origin: [-513.631222, 1.709453, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map7.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map7.pgm new file mode 100644 index 0000000..aa732a8 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map7.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map7.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map7.yaml new file mode 100644 index 0000000..354631b --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map7.yaml @@ -0,0 +1,6 @@ +image: ./map7.pgm +resolution: 0.1 +origin: [-410.819813, -26.960649, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map8.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/map8.pgm new file mode 100644 index 0000000..4955186 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map8.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/map8.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/map8.yaml new file mode 100644 index 0000000..334008f --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/map8.yaml @@ -0,0 +1,6 @@ +image: ./map8.pgm +resolution: 0.1 +origin: [-273.169153, -70.548067, 0.0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/merged_map.pgm b/src/tsukuba2022/multimaps/tsukuba-distorted/merged_map.pgm new file mode 100644 index 0000000..2915cab --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/merged_map.pgm Binary files differ diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/merged_map.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/merged_map.yaml new file mode 100644 index 0000000..0887a4b --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/merged_map.yaml @@ -0,0 +1,6 @@ +image: ./merged_map.pgm +resolution: 0.1 +origin: [-655.682101, -89.185045, 0] +negate: 0 +occupied_thresh: 0.65 +free_thresh: 0.196 diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_L.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_L.yaml new file mode 100644 index 0000000..b79f1fb --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_L.yaml @@ -0,0 +1,387 @@ +waypoints: +- point: {x: 6.773622, y: 3.509047, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 16.949907, y: 3.772681, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 27.864368, y: 3.930862, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 38.831555, y: 3.825408, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 48.257282, y: 3.405931, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 55.5451, y: 1.66404, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 58.0735, y: 0.128874, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 61.313, y: -6.31239, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 64.9454, y: -14.2518, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 1} +- point: {x: 67.6144, y: -15.4014, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: 70.316, y: -15.5441, z: 0, vel: 0.5, rad: 0.8, stop: false} +- point: {x: 74.2391, y: -15.3596, z: 0, vel: 0.5, rad: 0.8, stop: false} +- point: {x: 77.357, y: -15.2531, z: 0, vel: 0.4, rad: 0.8, stop: false, tandem_end: 1} +- point: {x: 79.101358, y: -15.32212, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 80.470272, y: -16.227709, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 81.691765, y: -17.449202, z: 0, vel: 0.3, rad: 0.5, stop: false, tandem_start: 2} +- point: {x: 83.0514, y: -18.1883, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 85.4238, y: -18.5438, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 87.9159, y: -17.5321, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 88.2617, y: -15.0813, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 88.16, y: -10.9362, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 88.0087, y: -6.39951, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 87.986905, y: -2.248267, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 87.838577, y: 3.197497, z: 0, vel: 1, rad: 1, stop: false, tandem_end: 2} +- point: {x: 84.1737, y: 4.69392, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 80.0329, y: 4.54753, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 74.1995, y: 2.24651, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 69.9941, y: -0.0748514, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 63.1423, y: -4.43719, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 59.449401, y: -7.597903, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 3} +- point: {x: 55.4954, y: -9.77409, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 51.7554, y: -10.206, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 48.1474, y: -10.3002, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 46.051, y: -11.3614, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.5089, y: -11.9516, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 39.952037, y: -12.078326, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 37.4443, y: -12.0861, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 35.196419, y: -12.32575, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.149688, y: -14.419212, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 33.7788, y: -17.3731, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 32.519273, y: -19.091731, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 28.181658, y: -19.485825, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 23.802938, y: -19.012541, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 21.2425, y: -18.9, z: 0, vel: 0.3, rad: 0.4, stop: false} +- point: {x: 19.363355, y: -18.9, z: 0, vel: 0.3, rad: 0.4, stop: false} +- point: {x: 17.5523, y: -18.9, z: 0, vel: 0.3, rad: 0.4, stop: false} +- point: {x: 15.426, y: -18.7627, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 12.495, y: -18.5628, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 10.0156, y: -18.6638, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 7.584379, y: -18.876842, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 6.06788, y: -21.9222, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 5.635294, y: -26.384429, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 0.550092, y: -27.6913, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: -5.94073, y: -28.0941, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -10.5427, y: -28.3094, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -16.6638, y: -28.2209, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -23.610529, y: -28.018403, z: 0, vel: 0.5, rad: 1, stop: true, tandem_end: 3} +- point: {x: -34.563433, y: -33.284636, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -43.9865, y: -35.5365, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -49.5035, y: -37.0547, z: 0, vel: 1, rad: 1, stop: false, change_map: 1} +- point: {x: -55.456486, y: -38.249474, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -59.5, y: -38.371756, z: 0, vel: 0.4, rad: 1, stop: true} +- point: {x: -65.943953, y: -37.689411, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -74.81612, y: -36.802698, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -85.959427, y: -37.160527, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -98.098295, y: -37.1428, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -112.776422, y: -37.5921, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -124.677948, y: -38.360256, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -132.168997, y: -39.607726, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -136.2, y: -39.646878, z: 0, vel: 0.4, rad: 1, stop: true} +- point: {x: -143.67858, y: -39.737603, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -152.926109, y: -39.669051, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -162.943162, y: -39.534928, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -170.565596, y: -39.847804, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -178.093328, y: -40.045443, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -186.095899, y: -40.277128, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -192.807681, y: -40.580631, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -199.954229, y: -41.01592, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -207.102087, y: -41.302253, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -213.580959, y: -41.433734, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -220.506696, y: -41.569149, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -226.472745, y: -40.727838, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.618631, y: -34.555822, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.053731, y: -30.284497, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.945311, y: -25.319456, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.933631, y: -21.352493, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.120785, y: -17.322888, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 4} +- point: {x: -230.20383, y: -13.726879, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.212516, y: -9.958163, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.335019, y: -6.237119, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.34413, y: -2.60572, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.428225, y: 0.974424, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.511919, y: 4.171533, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.562136, y: 7.837328, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.629091, y: 11.553339, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.729524, y: 15.202395, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.991153, y: 18.842095, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -231.195879, y: 22.85471, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -231.318714, y: 26.908271, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -231.495066, y: 30.723899, z: 0, vel: 0.4, rad: 0.5, stop: false} +- point: {x: -231.667824, y: 34.453931, z: 0, vel: 0.4, rad: 0.5, stop: false} +- point: {x: -232.052911, y: 38.468527, z: 0, vel: 0.3, rad: 1, stop: true, tandem_end: 4} +- point: {x: -232.168136, y: 39.914256, z: 0.0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: -233.55, y: 41.671807, z: 0, vel: 0.3, rad: 1, stop: true} +- point: {x: -247.495828, y: 41.235564, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -250.089691, y: 39.72945, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -250.121071, y: 37.938807, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -250.167211, y: 33.373389, z: 0.0, vel: 0.5, rad: 1, stop: false} +- point: {x: -251.357335, y: 31.159574, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -258.370021, y: 27.509832, z: 0, vel: 1, rad: 1, stop: true, change_map: 2} +- point: {x: -264.396474, y: 26.947688, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -270.857705, y: 26.159871, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -277.85906, y: 25.580321, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -283.757645, y: 25.06385, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -288.52595, y: 24.424129, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -293.766978, y: 23.957402, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -299.650084, y: 23.425189, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -306.053285, y: 23.221736, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -312.564439, y: 22.824473, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -320.498546, y: 21.696156, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -328.572465, y: 21.544269, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -336.974651, y: 21.255655, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -344.726775, y: 20.649657, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -349.430935, y: 20.204442, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -356.439539, y: 19.793312, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -362.670675, y: 19.200813, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -369.515614, y: 18.240601, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -376.584151, y: 16.91525, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.707911, y: 15.479454, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -391.549569, y: 14.816778, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -399.833011, y: 14.09888, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -407.509, y: 13.436205, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -415.594379, y: 12.754536, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -423.964481, y: 11.912516, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -434.126516, y: 10.413478, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -442.190996, y: 9.075602, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -450.360809, y: 8.381359, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -457.765256, y: 7.521008, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -464.230633, y: 6.964717, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -468.915726, y: 6.617103, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -473.671049, y: 6.265773, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -478.478836, y: 5.79059, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -483.917892, y: 5.108712, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -489.729853, y: 4.458736, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -494.791098, y: 3.683622, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -499.857248, y: 2.969839, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -504.695292, y: 1.898587, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -513.496072, y: -0.488834, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -521.321153, y: -0.462393, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -523.439013, y: 4.067211, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: -524.728838, y: 10.720685, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -525.450965, y: 17.73563, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -525.382191, y: 23.787739, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -522.078306, y: 27.147941, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -513.178587, y: 28.692355, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -506.891215, y: 29.18228, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -501.126877, y: 29.652821, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -494.872156, y: 30.273185, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -489.722941, y: 30.83907, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -483.253093, y: 31.419368, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -476.572253, y: 31.79352, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -469.057003, y: 32.698101, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -463.872077, y: 33.248951, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -457.571322, y: 33.960177, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -452.826458, y: 34.66576, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -446.818809, y: 34.802769, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -442.718328, y: 35.164752, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -439.924611, y: 35.381396, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -436.220623, y: 35.759652, z: 0.0, vel: 1, rad: 0.8, stop: false} +- point: {x: -432.313063, y: 36.211514, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -427.79953, y: 37.39299, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -422.16427, y: 38.096614, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -415.972598, y: 38.591151, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -411.635111, y: 38.900458, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -406.824537, y: 39.434968, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -400.636853, y: 40.099432, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -394.744564, y: 40.569094, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -389.705919, y: 41.03043, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.954122, y: 41.05134, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.153314, y: 41.00887, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 5} +- point: {x: -378.233803, y: 42.941562, z: 0, vel: 0.4, rad: 1, stop: true, tandem_end: 5} +- point: {x: -378.950597, y: 52.225902, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -378.992187, y: 56.01483, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -378.610936, y: 61.437047, z: 0, vel: 0.5, rad: 1, stop: true, change_map: 3} +- point: {x: -377.214457, y: 69.803004, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.375104, y: 77.04998, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.285855, y: 83.029627, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.268006, y: 90.062407, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.464352, y: 94.863975, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.303705, y: 101.825356, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.250156, y: 107.822854, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.232306, y: 115.391124, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.535751, y: 121.567119, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -379.371782, y: 124.073212, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -382.077034, y: 124.93606, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -386.325418, y: 124.671318, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -391.485026, y: 124.50215, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -398.516025, y: 124.499962, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -406.877301, y: 124.32455, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -418.746804, y: 124.441491, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -430.557837, y: 124.383021, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -443.012045, y: 124.090669, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -454.296844, y: 124.20761, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -466.692581, y: 124.032198, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -481.724596, y: 123.560639, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -496.218746, y: 123.553514, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -508.104505, y: 123.488741, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -517.17266, y: 123.488741, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -526.564677, y: 123.359196, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -536.151012, y: 123.197265, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -545.899278, y: 123.132492, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -555.032205, y: 123.002947, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -563.873656, y: 122.873402, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -573.36834, y: 123.12865, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -580.83126, y: 124.848606, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -587.065386, y: 126.513058, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -590.595544943929, y: 128.4892258736552, z: 0, vel: 1, rad: 1, stop: true, change_map: 4} +- point: {x: -591.276404, y: 133.725498, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.301951, y: 140.152756, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.137394, y: 145.058199, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.038719, y: 152.54109, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -591.874259, y: 160.270669, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -591.890705, y: 169.052786, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.844568, y: 177.423756, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -593.913553, y: 184.035013, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -594.538497, y: 189.182583, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.327901, y: 195.760948, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.673265, y: 202.947812, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.821278, y: 209.739974, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.49236, y: 216.384123, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.278563, y: 222.584232, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.295009, y: 228.406085, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.163442, y: 233.948358, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.709395, y: 239.979678, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -596.117305, y: 246.365022, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -596.906709, y: 251.660606, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -597.877018, y: 256.561488, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -598.5513, y: 261.215682, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -599.371761, y: 265.890632, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -599.696068, y: 271.1525, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.6079862914644, y: 274.3467234463298, z: 0, vel: 1, rad: 1, stop: true, change_map: 5} +- point: {x: -584.191131, y: 274.687905, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -576.709871, y: 275.007617, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -569.398141, y: 275.159342, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -559.155964, y: 275.633517, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -549.252472, y: 276.090399, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -540.298138, y: 276.461563, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -532.602171, y: 276.885339, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -525.350358, y: 276.790915, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -519.132686, y: 275.864547, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -514.200245, y: 274.502299, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -508.227567, y: 272.897518, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -501.385731, y: 270.979247, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -495.526145, y: 269.514109, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -490.134145, y: 268.027609, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -483.389145, y: 266.637729, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -474.529926, y: 264.904719, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -466.792896, y: 264.073468, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -458.800097, y: 263.817699, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -451.639291, y: 263.582959, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -444.511708, y: 263.730871, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -437.268023, y: 264.399519, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -431.175897, y: 265.588226, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -424.590916, y: 267.526357, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -417.765145, y: 269.686819, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -411.035129, y: 272.066267, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -404.118325, y: 274.908777, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -399.854263, y: 276.282435, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -395.504347, y: 277.913653, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -392.041584, y: 279.945522, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -390.322707, y: 282.423672, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -388.647054, y: 284.921601, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -385.710258, y: 284.572675, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.521322, y: 281.254341, z: 0, vel: 1, rad: 1, stop: true, change_map: 6} +- point: {x: -380.872344, y: 276.630919, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.717063, y: 272.430668, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -373.973464, y: 266.214851, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -372.663103, y: 263.000792, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -371.46926, y: 258.507752, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -370.461787, y: 254.166303, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -368.666508, y: 249.453696, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -366.42241, y: 244.628883, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -364.163334, y: 240.018282, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -361.201123, y: 234.430476, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -359.046789, y: 228.909993, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -358.373559, y: 223.389511, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -357.431037, y: 218.205643, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -355.478672, y: 212.483191, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -353.187212, y: 207.014325, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -351.687228, y: 202.032903, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -349.884503, y: 197.791435, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -347.835323, y: 194.227758, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -346.010921, y: 191.309758, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -343.311483, y: 189.394539, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -340.075278, y: 187.216614, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -336.379497, y: 184.77518, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -333.103529, y: 182.333095, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -329.648872, y: 180.427078, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -326.015526, y: 178.282808, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -322.304772, y: 176.183982, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -318.629709, y: 173.577327, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -313.805102, y: 169.824855, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -311.184328, y: 166.78714, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -309.099621, y: 162.379475, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -307.848797, y: 157.733557, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -306.776662, y: 152.015504, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.883217, y: 146.237889, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.16846, y: 141.651534, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -304.096325, y: 135.754793, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -303.02419, y: 130.215429, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -302.130745, y: 125.688638, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -301.148834, y: 121.985696, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -300.280066, y: 119.109411, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -298.733691, y: 113.05039, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -296.933927, y: 108.746997, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -295.626204, y: 105.165568, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -295.19533, y: 101.35897, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -296.87661, y: 98.128944, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.860672, y: 90.759765, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -324.10629, y: 83.833735, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -341.525633, y: 78.273633, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -346.41817, y: 72.609748, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -350.543536, y: 67.185716, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 6} +- point: {x: -352.444825, y: 63.852853, z: 0, vel: 1, rad: 0.3, stop: false} +- point: {x: -352.032273, y: 58.855008, z: 0, vel: 1, rad: 1, stop: true, tandem_end: 6} +- point: {x: -350.310063, y: 50.115945, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: -346.978463, y: 49.063552, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -342.73747, y: 51.032147, z: 0, vel: 1, rad: 1, stop: true, change_map: 7} +- point: {x: -337.170704, y: 52.057963, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -332.489726, y: 52.818894, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -327.273472, y: 53.531045, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -320.222558, y: 54.629153, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -312.791917, y: 55.938415, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.446026, y: 56.916502, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -298.30757, y: 58.259444, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -289.908277, y: 60.175644, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -281.887594, y: 61.780237, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -273.312668, y: 63.75541, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -264.874435, y: 65.684603, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -256.900304, y: 67.4288, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -250.70504, y: 68.906349, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -243.878649, y: 69.883168, z: 0, vel: 0.5, rad: 0.5, stop: false, tandem_start: 7} +- point: {x: -238.847343, y: 68.291878, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -234.431005, y: 66.228349, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -230.798112, y: 64.717305, z: 0, vel: 0.5, rad: 0.5, stop: true, tandem_end: 7} +- point: {x: -224.387161, y: 65.799655, z: 0.0, vel: 0.5, rad: 1, stop: true} +- point: {x: -208.179028, y: 70.455454, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -207.145701, y: 67.794993, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -206.21952842992044, y: 64.55573822412595, z: 0, vel: 1, rad: 1, stop: true, change_map: 8} +- point: {x: -205.773051, y: 61.988886, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -204.867894, y: 57.233814, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -203.42246, y: 51.855124, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -201.89186, y: 45.955936, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -200.93136, y: 40.670677, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -199.755397, y: 35.464946, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -198.352346, y: 28.928007, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -196.761001, y: 22.789819, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -195.491101, y: 17.081555, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -194.246347, y: 10.794921, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -193.10218, y: 4.244249, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -191.882573, y: -1.82864, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -191.062153, y: -8.430282, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -185.318107, y: -14.973648, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -176.597443, y: -13.172921, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -168.688542, y: -11.390633, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -160.570971, y: -9.365669, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -152.636452, y: -7.477202, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -144.750892, y: -5.929091, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -136.073335, y: -3.853563, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -127.132434, y: -1.745545, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -118.845745, y: 0.071711, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -111.067888, y: 1.634551, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -105.826197, y: 2.820748, z: 0.0, vel: 1, rad: 1, stop: true} +- point: {x: -98.397016, y: 4.612244, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -90.452455, y: 6.306353, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -81.96203, y: 8.372655, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -73.505953, y: 10.033028, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -65.03958, y: 11.426952, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -55.556593, y: 13.559053, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -45.411131, y: 15.903344, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -37.255361, y: 17.558138, z: 0.0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500880.699932, frame_id: map} + pose: + position: {x: -31.6919340831112, y: 18.795976159259887, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.11732158139368357, w: 0.9930939766906681} \ No newline at end of file diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_R.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_R.yaml new file mode 100644 index 0000000..e1d3952 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_R.yaml @@ -0,0 +1,387 @@ +waypoints: +- point: {x: 7.913908, y: 0.625135, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 17.873427, y: 1.284221, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 28.2563, y: 1.64634, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 38.1161, y: 1.91456, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 48.2937, y: 1.73542, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 55.5451, y: 1.66404, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 58.0735, y: 0.128874, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 61.313, y: -6.31239, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 64.9454, y: -14.2518, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 1} +- point: {x: 67.6144, y: -15.4014, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: 70.316, y: -15.5441, z: 0, vel: 0.5, rad: 0.8, stop: false} +- point: {x: 74.2391, y: -15.3596, z: 0, vel: 0.5, rad: 0.8, stop: false} +- point: {x: 77.357, y: -15.2531, z: 0, vel: 0.4, rad: 0.8, stop: false, tandem_end: 1} +- point: {x: 79.101358, y: -15.32212, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 80.470272, y: -16.227709, z: 0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: 81.691765, y: -17.449202, z: 0, vel: 0.3, rad: 0.5, stop: false, tandem_start: 2} +- point: {x: 83.0514, y: -18.1883, z: 0, vel: 0.3, rad: 1, stop: false} +- point: {x: 85.4238, y: -18.5438, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 87.9159, y: -17.5321, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 88.2617, y: -15.0813, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 88.16, y: -10.9362, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 88.0087, y: -6.39951, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 87.986905, y: -2.248267, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 87.838577, y: 3.197497, z: 0, vel: 1, rad: 1, stop: false, tandem_end: 2} +- point: {x: 84.1737, y: 4.69392, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 80.0329, y: 4.54753, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 74.1995, y: 2.24651, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 69.9941, y: -0.0748514, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 63.1423, y: -4.43719, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 59.449401, y: -7.597903, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 3} +- point: {x: 55.4954, y: -9.77409, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 51.7554, y: -10.206, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 48.1474, y: -10.3002, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 46.051, y: -11.3614, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 42.5089, y: -11.9516, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 39.952037, y: -12.078326, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: 37.4443, y: -12.0861, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 35.196419, y: -12.32575, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 34.149688, y: -14.419212, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 33.7788, y: -17.3731, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 32.519273, y: -19.091731, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 28.181658, y: -19.485825, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 23.802938, y: -19.012541, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 21.2425, y: -18.9, z: 0, vel: 0.3, rad: 0.4, stop: false} +- point: {x: 19.363355, y: -18.9, z: 0, vel: 0.3, rad: 0.4, stop: false} +- point: {x: 17.5523, y: -18.9, z: 0, vel: 0.3, rad: 0.4, stop: false} +- point: {x: 15.426, y: -18.7627, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 12.495, y: -18.5628, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 10.0156, y: -18.6638, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 7.584379, y: -18.876842, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 6.06788, y: -21.9222, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: 5.635294, y: -26.384429, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 0.550092, y: -27.6913, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: -5.94073, y: -28.0941, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -10.5427, y: -28.3094, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -16.6638, y: -28.2209, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -23.610529, y: -28.018403, z: 0, vel: 0.5, rad: 1, stop: true, tandem_end: 3} +- point: {x: -34.563433, y: -33.284636, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -43.9865, y: -35.5365, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -49.5035, y: -37.0547, z: 0, vel: 1, rad: 1, stop: false, change_map: 1} +- point: {x: -55.456486, y: -38.249474, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -59.5, y: -38.371756, z: 0, vel: 0.4, rad: 1, stop: true} +- point: {x: -65.943953, y: -37.689411, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -74.81612, y: -36.802698, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -85.959427, y: -37.160527, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -98.098295, y: -37.1428, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -112.776422, y: -37.5921, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -124.677948, y: -38.360256, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -132.168997, y: -39.607726, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -136.2, y: -39.646878, z: 0, vel: 0.4, rad: 1, stop: true} +- point: {x: -143.67858, y: -39.737603, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -152.926109, y: -39.669051, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -162.943162, y: -39.534928, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -170.565596, y: -39.847804, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -178.093328, y: -40.045443, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -186.095899, y: -40.277128, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -192.807681, y: -40.580631, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -199.954229, y: -41.01592, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -207.102087, y: -41.302253, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -213.580959, y: -41.433734, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -220.506696, y: -41.569149, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -226.472745, y: -40.727838, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.618631, y: -34.555822, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.053731, y: -30.284497, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.945311, y: -25.319456, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -229.933631, y: -21.352493, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.120785, y: -17.322888, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 4} +- point: {x: -230.20383, y: -13.726879, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.212516, y: -9.958163, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.335019, y: -6.237119, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.34413, y: -2.60572, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.428225, y: 0.974424, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.511919, y: 4.171533, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.562136, y: 7.837328, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.629091, y: 11.553339, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -230.729524, y: 15.202395, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -230.991153, y: 18.842095, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -231.195879, y: 22.85471, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -231.318714, y: 26.908271, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -231.495066, y: 30.723899, z: 0, vel: 0.4, rad: 0.5, stop: false} +- point: {x: -231.667824, y: 34.453931, z: 0, vel: 0.4, rad: 0.5, stop: false} +- point: {x: -232.052911, y: 38.468527, z: 0, vel: 0.3, rad: 1, stop: true, tandem_end: 4} +- point: {x: -232.168136, y: 39.914256, z: 0.0, vel: 0.3, rad: 0.5, stop: false} +- point: {x: -233.55, y: 41.671807, z: 0, vel: 0.3, rad: 1, stop: true} +- point: {x: -247.495828, y: 41.235564, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -250.089691, y: 39.72945, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -250.121071, y: 37.938807, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -250.167211, y: 33.373389, z: 0.0, vel: 0.5, rad: 1, stop: false} +- point: {x: -251.357335, y: 31.159574, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -258.370021, y: 27.509832, z: 0, vel: 1, rad: 1, stop: true, change_map: 2} +- point: {x: -264.396474, y: 26.947688, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -270.857705, y: 26.159871, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -277.85906, y: 25.580321, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -283.757645, y: 25.06385, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -288.52595, y: 24.424129, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -293.766978, y: 23.957402, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -299.650084, y: 23.425189, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -306.053285, y: 23.221736, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -312.564439, y: 22.824473, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -320.498546, y: 21.696156, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -328.572465, y: 21.544269, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -336.974651, y: 21.255655, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -344.726775, y: 20.649657, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -349.430935, y: 20.204442, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -356.439539, y: 19.793312, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -362.670675, y: 19.200813, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -369.515614, y: 18.240601, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -376.584151, y: 16.91525, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.707911, y: 15.479454, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -391.549569, y: 14.816778, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -399.833011, y: 14.09888, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -407.509, y: 13.436205, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -415.594379, y: 12.754536, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -423.964481, y: 11.912516, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -434.126516, y: 10.413478, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -442.190996, y: 9.075602, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -450.360809, y: 8.381359, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -457.765256, y: 7.521008, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -464.230633, y: 6.964717, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -468.915726, y: 6.617103, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -473.671049, y: 6.265773, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -478.478836, y: 5.79059, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -483.917892, y: 5.108712, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -489.729853, y: 4.458736, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -494.791098, y: 3.683622, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -499.857248, y: 2.969839, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -504.695292, y: 1.898587, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -513.496072, y: -0.488834, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -521.321153, y: -0.462393, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -523.439013, y: 4.067211, z: 0, vel: 0.4, rad: 1, stop: false} +- point: {x: -524.728838, y: 10.720685, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -525.450965, y: 17.73563, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -525.382191, y: 23.787739, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -522.078306, y: 27.147941, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -513.178587, y: 28.692355, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -506.891215, y: 29.18228, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -501.126877, y: 29.652821, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -494.872156, y: 30.273185, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -489.722941, y: 30.83907, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -483.253093, y: 31.419368, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -476.572253, y: 31.79352, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -469.057003, y: 32.698101, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -463.872077, y: 33.248951, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -457.571322, y: 33.960177, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -452.826458, y: 34.66576, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -446.818809, y: 34.802769, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -442.718328, y: 35.164752, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -439.924611, y: 35.381396, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -436.220623, y: 35.759652, z: 0.0, vel: 1, rad: 0.8, stop: false} +- point: {x: -432.313063, y: 36.211514, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -427.79953, y: 37.39299, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -422.16427, y: 38.096614, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -415.972598, y: 38.591151, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -411.635111, y: 38.900458, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -406.824537, y: 39.434968, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -400.636853, y: 40.099432, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -394.744564, y: 40.569094, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -389.705919, y: 41.03043, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.954122, y: 41.05134, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -380.153314, y: 41.00887, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 5} +- point: {x: -378.233803, y: 42.941562, z: 0, vel: 0.4, rad: 1, stop: true, tandem_end: 5} +- point: {x: -378.950597, y: 52.225902, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -378.992187, y: 56.01483, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -378.610936, y: 61.437047, z: 0, vel: 0.5, rad: 1, stop: true, change_map: 3} +- point: {x: -377.214457, y: 69.803004, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.375104, y: 77.04998, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.285855, y: 83.029627, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.268006, y: 90.062407, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.464352, y: 94.863975, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.303705, y: 101.825356, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.250156, y: 107.822854, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.232306, y: 115.391124, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.535751, y: 121.567119, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -379.371782, y: 124.073212, z: 0, vel: 0.5, rad: 1, stop: false} +- point: {x: -382.077034, y: 124.93606, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -386.325418, y: 124.671318, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -391.485026, y: 124.50215, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -398.516025, y: 124.499962, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -406.877301, y: 124.32455, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -418.746804, y: 124.441491, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -430.557837, y: 124.383021, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -443.012045, y: 124.090669, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -454.296844, y: 124.20761, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -466.692581, y: 124.032198, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -481.724596, y: 123.560639, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -496.218746, y: 123.553514, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -508.104505, y: 123.488741, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -517.17266, y: 123.488741, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -526.564677, y: 123.359196, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -536.151012, y: 123.197265, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -545.899278, y: 123.132492, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -555.032205, y: 123.002947, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -563.873656, y: 122.873402, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -573.36834, y: 123.12865, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -580.83126, y: 124.848606, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -587.065386, y: 126.513058, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -590.595544943929, y: 128.4892258736552, z: 0, vel: 1, rad: 1, stop: true, change_map: 4} +- point: {x: -591.276404, y: 133.725498, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.301951, y: 140.152756, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.137394, y: 145.058199, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.038719, y: 152.54109, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -591.874259, y: 160.270669, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -591.890705, y: 169.052786, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.844568, y: 177.423756, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -593.913553, y: 184.035013, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -594.538497, y: 189.182583, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.327901, y: 195.760948, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.673265, y: 202.947812, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.821278, y: 209.739974, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.49236, y: 216.384123, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.278563, y: 222.584232, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.295009, y: 228.406085, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.163442, y: 233.948358, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -595.709395, y: 239.979678, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -596.117305, y: 246.365022, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -596.906709, y: 251.660606, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -597.877018, y: 256.561488, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -598.5513, y: 261.215682, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -599.371761, y: 265.890632, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -599.696068, y: 271.1525, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -592.6079862914644, y: 274.3467234463298, z: 0, vel: 1, rad: 1, stop: true, change_map: 5} +- point: {x: -584.191131, y: 274.687905, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -576.709871, y: 275.007617, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -569.398141, y: 275.159342, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -559.155964, y: 275.633517, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -549.252472, y: 276.090399, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -540.298138, y: 276.461563, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -532.602171, y: 276.885339, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -525.350358, y: 276.790915, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -519.132686, y: 275.864547, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -514.200245, y: 274.502299, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -508.227567, y: 272.897518, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -501.385731, y: 270.979247, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -495.526145, y: 269.514109, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -490.134145, y: 268.027609, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -483.389145, y: 266.637729, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -474.529926, y: 264.904719, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -466.792896, y: 264.073468, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -458.800097, y: 263.817699, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -451.639291, y: 263.582959, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -444.511708, y: 263.730871, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -437.268023, y: 264.399519, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -431.175897, y: 265.588226, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -424.590916, y: 267.526357, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -417.765145, y: 269.686819, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -411.035129, y: 272.066267, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -404.118325, y: 274.908777, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -399.854263, y: 276.282435, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -395.504347, y: 277.913653, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -392.041584, y: 279.945522, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -390.322707, y: 282.423672, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -388.647054, y: 284.921601, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -385.710258, y: 284.572675, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -383.521322, y: 281.254341, z: 0, vel: 1, rad: 1, stop: true, change_map: 6} +- point: {x: -380.872344, y: 276.630919, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -377.717063, y: 272.430668, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -373.973464, y: 266.214851, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -372.663103, y: 263.000792, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -371.46926, y: 258.507752, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -370.461787, y: 254.166303, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -368.666508, y: 249.453696, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -366.42241, y: 244.628883, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -364.163334, y: 240.018282, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -361.201123, y: 234.430476, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -359.046789, y: 228.909993, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -358.373559, y: 223.389511, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -357.431037, y: 218.205643, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -355.478672, y: 212.483191, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -353.187212, y: 207.014325, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -351.687228, y: 202.032903, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -349.884503, y: 197.791435, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -347.835323, y: 194.227758, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -346.010921, y: 191.309758, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -343.311483, y: 189.394539, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -340.075278, y: 187.216614, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -336.379497, y: 184.77518, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -333.103529, y: 182.333095, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -329.648872, y: 180.427078, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -326.015526, y: 178.282808, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -322.304772, y: 176.183982, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -318.629709, y: 173.577327, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -313.805102, y: 169.824855, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -311.184328, y: 166.78714, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -309.099621, y: 162.379475, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -307.848797, y: 157.733557, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -306.776662, y: 152.015504, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.883217, y: 146.237889, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.16846, y: 141.651534, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -304.096325, y: 135.754793, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -303.02419, y: 130.215429, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -302.130745, y: 125.688638, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -301.148834, y: 121.985696, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -300.280066, y: 119.109411, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -298.733691, y: 113.05039, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -296.933927, y: 108.746997, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -295.626204, y: 105.165568, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -295.19533, y: 101.35897, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -296.87661, y: 98.128944, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.860672, y: 90.759765, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -324.10629, y: 83.833735, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -341.525633, y: 78.273633, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -346.41817, y: 72.609748, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -350.543536, y: 67.185716, z: 0, vel: 1, rad: 1, stop: false, tandem_start: 6} +- point: {x: -352.444825, y: 63.852853, z: 0, vel: 1, rad: 0.3, stop: false} +- point: {x: -352.032273, y: 58.855008, z: 0, vel: 1, rad: 1, stop: true, tandem_end: 6} +- point: {x: -350.310063, y: 50.115945, z: 0, vel: 1, rad: 0.5, stop: false} +- point: {x: -346.978463, y: 49.063552, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -342.73747, y: 51.032147, z: 0, vel: 1, rad: 1, stop: true, change_map: 7} +- point: {x: -337.170704, y: 52.057963, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -332.489726, y: 52.818894, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -327.273472, y: 53.531045, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -320.222558, y: 54.629153, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -312.791917, y: 55.938415, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -305.446026, y: 56.916502, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -298.30757, y: 58.259444, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -289.908277, y: 60.175644, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -281.887594, y: 61.780237, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -273.312668, y: 63.75541, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -264.874435, y: 65.684603, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -256.900304, y: 67.4288, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -250.70504, y: 68.906349, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -243.878649, y: 69.883168, z: 0, vel: 0.5, rad: 0.5, stop: false, tandem_start: 7} +- point: {x: -238.847343, y: 68.291878, z: 0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -234.431005, y: 66.228349, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: -230.798112, y: 64.717305, z: 0, vel: 0.5, rad: 0.5, stop: true, tandem_end: 7} +- point: {x: -224.387161, y: 65.799655, z: 0.0, vel: 0.5, rad: 1, stop: true} +- point: {x: -208.179028, y: 70.455454, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -207.145701, y: 67.794993, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -206.21952842992044, y: 64.55573822412595, z: 0, vel: 1, rad: 1, stop: true, change_map: 8} +- point: {x: -205.773051, y: 61.988886, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: -204.867894, y: 57.233814, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -203.42246, y: 51.855124, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -201.89186, y: 45.955936, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -200.93136, y: 40.670677, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -199.755397, y: 35.464946, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -198.352346, y: 28.928007, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -196.761001, y: 22.789819, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -195.491101, y: 17.081555, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -194.246347, y: 10.794921, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -193.10218, y: 4.244249, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -191.882573, y: -1.82864, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -191.062153, y: -8.430282, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -185.318107, y: -14.973648, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -176.597443, y: -13.172921, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -168.688542, y: -11.390633, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -160.570971, y: -9.365669, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -152.636452, y: -7.477202, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -144.750892, y: -5.929091, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -136.073335, y: -3.853563, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -127.132434, y: -1.745545, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -118.845745, y: 0.071711, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -111.067888, y: 1.634551, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -105.826197, y: 2.820748, z: 0.0, vel: 1, rad: 1, stop: true} +- point: {x: -98.397016, y: 4.612244, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -90.452455, y: 6.306353, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -81.96203, y: 8.372655, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -73.505953, y: 10.033028, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -65.03958, y: 11.426952, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -55.556593, y: 13.559053, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -45.411131, y: 15.903344, z: 0.0, vel: 1, rad: 1, stop: false} +- point: {x: -37.255361, y: 17.558138, z: 0.0, vel: 1, rad: 1, stop: false} +finish_pose: + header: {seq: 0, stamp: 1666500880.699932, frame_id: map} + pose: + position: {x: -31.6919340831112, y: 18.795976159259887, z: 0} + orientation: {x: 0.0, y: 0.0, z: 0.11732158139368357, w: 0.9930939766906681} diff --git a/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_first5.yaml b/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_first5.yaml new file mode 100644 index 0000000..23fcd84 --- /dev/null +++ b/src/tsukuba2022/multimaps/tsukuba-distorted/waypoints_first5.yaml @@ -0,0 +1,14 @@ +waypoints_L_first5: +- point: {x: 6.773622, y: 3.509047, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 16.949907, y: 3.772681, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 27.864368, y: 3.930862, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 38.831555, y: 3.825408, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 48.257282, y: 3.405931, z: 0, vel: 1, rad: 1, stop: false} + + +waypoints_R_first5: +- point: {x: 7.913908, y: 0.625135, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 17.873427, y: 1.284221, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 28.2563, y: 1.64634, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 38.1161, y: 1.91456, z: 0, vel: 1, rad: 1, stop: false} +- point: {x: 48.2937, y: 1.73542, z: 0, vel: 1, rad: 1, stop: false} diff --git a/src/tsukuba2022/params/base_global_planner_params.yaml b/src/tsukuba2022/params/base_global_planner_params.yaml index 267db3d..f4af45e 100644 --- a/src/tsukuba2022/params/base_global_planner_params.yaml +++ b/src/tsukuba2022/params/base_global_planner_params.yaml @@ -1,6 +1,6 @@ base_global_planner: global_planner/GlobalPlanner -GlobalPlanner: +GlobalPlanner: allow_unknown: true default_tolerance: 0.0 visualize_potential: false @@ -8,10 +8,12 @@ use_quadratic: true use_grid_path: false old_navfn_behavior: false - lethal_cost: 253 - neutral_cost: 66 - cost_factor: 0.55 + lethal_cost: 190 #180 #175 #150 #253 + neutral_cost: 123 #130 #150 #110 #66 + cost_factor: 0.4 #0.55 publish_potential: false orientation_mode: 0 orientation_window_size: 1 - outline_map: true \ No newline at end of file + outline_map: true + +# base_global_planner: carrot_planner/CarrotPlanner diff --git a/src/tsukuba2022/params/base_local_planner_params.yaml b/src/tsukuba2022/params/base_local_planner_params.yaml index 9ac04fc..7de1302 100644 --- a/src/tsukuba2022/params/base_local_planner_params.yaml +++ b/src/tsukuba2022/params/base_local_planner_params.yaml @@ -3,31 +3,31 @@ TrajectoryPlannerROS: # Robot Configuration Parameters holonomic_robot: false - acc_lim_x: 3.5 - acc_lim_theta: 1.0 #1.5 - max_vel_x: 2.0 - min_vel_x: 0.1 - max_vel_theta: 0.3 - min_vel_theta: -0.3 #-0.4 - min_in_place_vel_theta: 0.3 #0.2 - escape_vel: -0.2 + acc_lim_x: 3.5 #4.5 + acc_lim_theta: 1.2 #2.0 + max_vel_x: 1.2 + min_vel_x: 0.0 #0.1 + max_vel_theta: 1.0 + min_vel_theta: -1.0 + min_in_place_vel_theta: 0.2 + escape_vel: -0.3 # Goal Tolerance Parameters - yaw_goal_tolerance: 0.5 - xy_goal_tolerance: 0.4 + yaw_goal_tolerance: 0.3 + xy_goal_tolerance: 0.3 # Forward Simulation Parameters - sim_time: 3 + sim_time: 2.0 sim_granularity: 0.05 - vx_samples: 7 - vtheta_samples: 30 + vx_samples: 3 + vtheta_samples: 20 # Trajectory Scoring Parameters dwa: true meter_scoring: true - path_distance_bias: 0.4 #0.7 - goal_distance_bias: 1.0 #0.8 - occdist_scale : 0.05 #0.01 + path_distance_bias: 1.0 #0.8 #0.4 + goal_distance_bias: 0.6 #0.9 + occdist_scale : 0.01 #0.05 heading_lookahead: 0.325 - heading_scoring: true - heading_scoring_timestep: 1.2 + heading_scoring: false #true + heading_scoring_timestep: 1.0 diff --git a/src/tsukuba2022/params/costmap_common_params.yaml b/src/tsukuba2022/params/costmap_common_params.yaml deleted file mode 100644 index 13b542b..0000000 --- a/src/tsukuba2022/params/costmap_common_params.yaml +++ /dev/null @@ -1,18 +0,0 @@ -#max_obstacle_height: 0.60 # assume something like an arm is mounted on top of the robot -#obstacle_range: 4.0 #2.5 -#raytrace_range: 3.0 -#inflation_radius: 0.25 -#update_frequency: 2 - -#width: 5.0 -#height: 5.0 -#resolution: 0.15 - - -#observation_sources: scan point_cloud - -#scan: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, inf_is_valid: true, min_obstacle_height: 0.08, max_obstacle_height: 1.0} - -#point_cloud: {data_type: PointCloud, topic: /filtered_cloud, marking: true, clearing: true} - - diff --git a/src/tsukuba2022/params/emcl_params.yaml b/src/tsukuba2022/params/emcl_params.yaml new file mode 100644 index 0000000..4ed3fec --- /dev/null +++ b/src/tsukuba2022/params/emcl_params.yaml @@ -0,0 +1,31 @@ +odom_freq: 20 +num_particles: 500 + +odom_frame_id: odom +footprint_frame_id: base_footprint +base_frame_id: base_link + +initial_pose_x: 0.0 +initial_pose_y: 0.0 +initial_pose_a: 0.0 + +odom_fw_dev_per_fw: 0.05 #0.19 +odom_fw_dev_per_rot: 0.0001 +odom_rot_dev_per_fw: 0.1 #0.13 +odom_rot_dev_per_rot: 0.1 #0.2 + +laser_likelihood_max_dist: 0.2 + +alpha_threshold: 0.5 +open_space_threshold: 0.05 + +expansion_radius_position: 0.05 +expansion_radius_orientation: 0.1 + +range_threshold: 0.3 + +laser_min_range: 0.0 +laser_max_range: 100000000.0 + +scan_increment: 1 + diff --git a/src/tsukuba2022/params/foot_print.yaml b/src/tsukuba2022/params/foot_print.yaml index 9f9bd76..152c0b3 100644 --- a/src/tsukuba2022/params/foot_print.yaml +++ b/src/tsukuba2022/params/foot_print.yaml @@ -1 +1 @@ -footprint: [ [0.25, 0.4], [0.25, -0.4], [-0.65, -0.4], [-0.65, 0.4] ] +footprint: [ [0.2, 0.33], [0.2, -0.33], [-0.65, -0.33], [-0.65, 0.33] ] diff --git a/src/tsukuba2022/params/global_costmap_params.yaml b/src/tsukuba2022/params/global_costmap_params.yaml index 69534a3..f28f6a0 100644 --- a/src/tsukuba2022/params/global_costmap_params.yaml +++ b/src/tsukuba2022/params/global_costmap_params.yaml @@ -10,15 +10,48 @@ resolution: 0.1 plugins: - - {name: static_layer, type: "costmap_2d::StaticLayer"} - - {name: inflater_layer, type: "costmap_2d::InflationLayer"} + - {name: static_layer, type: "costmap_2d::StaticLayer"} + - {name: obstacle_layer1, type: "costmap_2d::ObstacleLayer"} + - {name: obstacle_layer2, type: "costmap_2d::ObstacleLayer"} + - {name: inflater_layer, type: "costmap_2d::InflationLayer"} static_layer: map_topic: map + first_map_only: false subscribe_to_updates: true lethal_cost_threshold: 50 track_unknown_space: false + obstacle_layer1: + observation_sources: scan + scan: + data_type: LaserScan + topic: /velodyne_scan + sensor_frame: velodyne_link + marking: true + clearing: true + inf_is_valid: true + max_obstacle_height: 2.5 + min_obstacle_height: 0.0 + obstacle_range: 10 + raytrace_range: 10 + observation_persistence: 0.0 + + obstacle_layer2: + observation_sources: scan + scan: + data_type: LaserScan + topic: /hokuyo_scan + sensor_frame: hokuyo_link + marking: true + clearing: true + inf_is_valid: true + max_obstacle_height: 0.3 + min_obstacle_height: 0.0 + obstacle_range: 3 + raytrace_range: 3 + observation_persistence: 0.0 + inflater_layer: - inflation_radius: 2.0 - cost_scaling_factor: 5.0 + inflation_radius: 5.0 #2.0 + cost_scaling_factor: 1.5 #5.0 diff --git a/src/tsukuba2022/params/gmapping_common_params.yaml b/src/tsukuba2022/params/gmapping_common_params.yaml index 0261dbb..fa712dc 100644 --- a/src/tsukuba2022/params/gmapping_common_params.yaml +++ b/src/tsukuba2022/params/gmapping_common_params.yaml @@ -4,7 +4,7 @@ map_frame: map odom_frame: odom map_update_interval: 2.0 -maxUrange: 40.0 +maxUrange: 60.0 #40 sigma: 0.05 kernelSize: 1 lstep: 0.05 @@ -12,7 +12,7 @@ iterations: 5 lsigma: 0.075 ogain: 3.0 -lskip: 1 +lskip: 0 #1 minimumScore: 0.0 srr: 0.01 srt: 0.02 @@ -23,11 +23,11 @@ temporalUpdate: -1.0 resampleThreshold: 0.5 particles: 20 -xmin: -60.0 -ymin: -60.0 -xmax: 60.0 -ymax: 60.0 -delta: 0.05 +xmin: -50.0 +ymin: -50.0 +xmax: 50.0 +ymax: 50.0 +delta: 0.1 #0.05 # Resolution of map llsamplerange: 0.01 llsamplestep: 0.01 lasamplerange: 0.005 diff --git a/src/tsukuba2022/params/local_costmap_params.yaml b/src/tsukuba2022/params/local_costmap_params.yaml index 2812066..58ca76f 100644 --- a/src/tsukuba2022/params/local_costmap_params.yaml +++ b/src/tsukuba2022/params/local_costmap_params.yaml @@ -1,10 +1,10 @@ local_costmap: global_frame: map robot_base_frame: base_footprint - update_frequency: 5.0 + update_frequency: 3.0 publish_frequency: 5.0 rolling_window: true - resolution: 0.05 + resolution: 0.1 width: 8 height: 8 always_send_full_costmap: true @@ -25,12 +25,12 @@ inf_is_valid: true max_obstacle_height: 2.5 min_obstacle_height: 0.0 - obstacle_range: 8 - raytrace_range: 8 + obstacle_range: 10 + raytrace_range: 10 observation_persistence: 0.0 inflater_layer: - inflation_radius: 0.4 - cost_scaling_factor: 5.0 + inflation_radius: 0.2 #0.3 + cost_scaling_factor: 30.0 # https://answers.ros.org/question/326867/local_costmap-not-showing-every-obstacle/ diff --git a/src/tsukuba2022/params/localization_params.yaml b/src/tsukuba2022/params/localization_params.yaml index 89604bb..e35535e 100644 --- a/src/tsukuba2022/params/localization_params.yaml +++ b/src/tsukuba2022/params/localization_params.yaml @@ -1,31 +1,32 @@ odom_model_type: diff -transform_tolerance: 0.5 #0.2 +transform_tolerance: 1.0 #0.5 #0.2 gui_publish_rate: 10.0 laser_max_beams: 30 min_particles: 100 max_particles: 4000 kld_err: 0.05 kld_z: 0.99 -odom_alpha1: 0.2 -odom_alpha2: 0.2 -odom_alpha3: 0.2 -odom_alpha4: 0.2 -laser_z_hit: 0.5 +odom_alpha1: 0.3 #0.2 +odom_alpha2: 0.3 #0.2 +odom_alpha3: 0.3 #0.2 +odom_alpha4: 0.3 #0.2 +laser_z_hit: 0.6 #0.75 #0.5 laser_z_short: 0.05 laser_z_max: 0.05 -laser_z_rand: 0.5 +laser_z_rand: 0.05 #0.5 laser_sigma_hit: 0.2 laser_lambda_short: 0.1 laser_lambda_short: 0.1 laser_model_type: likelihood_field laser_likelihood_max_dist: 2.0 -update_min_d: 0.2 +update_min_d: 0.3 #0.2 update_min_a: 0.5 global_frame_id: map odom_frame_id: odom base_frame_od: base_footprint resample_interval: 1 recovery_alpha_slow: 0.0 -recovery_alpha_fast: 0.0 +recovery_alpha_fast: 0.1 #0.0 reset_th_alpha: 0.003 +use_map_topic: true # true for map change diff --git a/src/tsukuba2022/params/move_base_params.yaml b/src/tsukuba2022/params/move_base_params.yaml index 5acfd08..2af0f38 100644 --- a/src/tsukuba2022/params/move_base_params.yaml +++ b/src/tsukuba2022/params/move_base_params.yaml @@ -3,12 +3,12 @@ # http://www.ros.org/wiki/move_base # -shutdown_costmaps: true +shutdown_costmaps: false # false for change map -controller_frequency: 6 -controller_patience: 3.0 +controller_frequency: 5 +controller_patience: 5.0 -planner_frequency: 0.5 +planner_frequency: 1.0 planner_patience: 5.0 oscillation_timeout: 10.0 diff --git a/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml b/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml index 4df1b20..8c63168 100644 --- a/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml +++ b/src/tsukuba2022/params/pointcloud_to_laserscan_params.yaml @@ -1,9 +1,9 @@ target_frame: velodyne_link # Leave disabled to output scan in pointcloud frame transform_tolerance: 0.01 -min_height: -0.7 #-0.4 +min_height: -0.8 #-0.7 #-0.4 max_height: 0.3 #1.5 -angle_min: -2.3565 -angle_max: 2.3565 +angle_min: -2.6178 #-2.4435 #-2.3565 +angle_max: 2.6178 #2.4435 #2.3565 angle_increment: 0.008711645 scan_time: 0.03333 range_min: 0.2 diff --git a/src/tsukuba2022/params/recovery_params.yaml b/src/tsukuba2022/params/recovery_params.yaml index 92afe1a..f996f20 100644 --- a/src/tsukuba2022/params/recovery_params.yaml +++ b/src/tsukuba2022/params/recovery_params.yaml @@ -1,4 +1,4 @@ recovery_behaviors: [{name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}, - {name: simple_lead_out, type: simple_lead_out/SimpleLeadOut}, - {name: rotate_recovery, type: rotate_recovery/RotateRecovery}, + #{name: simple_lead_out, type: simple_lead_out/SimpleLeadOut}, + #{name: rotate_recovery, type: rotate_recovery/RotateRecovery}, {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}] diff --git a/src/tsukuba2022/params/segmentation_params.yaml b/src/tsukuba2022/params/segmentation_params.yaml index 2a6b3af..49401d4 100644 --- a/src/tsukuba2022/params/segmentation_params.yaml +++ b/src/tsukuba2022/params/segmentation_params.yaml @@ -5,12 +5,12 @@ n_bins: 200 ## number of radial bins. n_segments: 720 ## number of radial segments. -max_dist_to_line: 0.35 #0.1 ## maximum vertical distance of point to line to be considered ground. +max_dist_to_line: 0.15 #0.35 #0.1 ## maximum vertical distance of point to line to be considered ground. sensor_height: 1.0 #1.205 # sensor height above ground. min_slope: 0.0 # minimum slope of a ground line. max_slope: 3.0 ## maximum slope of a ground line. -max_fit_error: 0.15 #0.05 # maximum error of a point during line fit. +max_fit_error: 0.07 #0.15 #0.05 # maximum error of a point during line fit. long_threshold: 10.0 ## distance between points after which they are considered far from each other. max_long_height: 0.3 # maximum height change to previous point in long line. max_start_height: 0.5 ## maximum difference to estimated ground height to start a new line. diff --git a/src/tsukuba2022/params/teb_local_planner_params.yaml b/src/tsukuba2022/params/teb_local_planner_params.yaml index e0531bc..118b4dc 100644 --- a/src/tsukuba2022/params/teb_local_planner_params.yaml +++ b/src/tsukuba2022/params/teb_local_planner_params.yaml @@ -7,16 +7,16 @@ # Trajectory teb_autosize: True - dt_ref: 0.5 #0.3 軌道の解像度[s] + dt_ref: 0.5 軌道の解像度[s] dt_hysteresis: 0.1 global_plan_overwrite_orientation: True - max_global_plan_lookahead_dist: 2.0 #仮想的なローカルゴールまでの距離 + max_global_plan_lookahead_dist: 5.0 #仮想的なローカルゴールまでの距離 feasibility_check_no_poses: 5 # Robot max_vel_x: 1.2 max_vel_x_backwards: 0.2 - max_vel_theta: 1.0 + max_vel_theta: 0.5 acc_lim_x: 2.0 acc_lim_theta: 1.0 min_turning_radius: 0.0 @@ -33,7 +33,7 @@ free_goal_vel: False # Obstacles - min_obstacle_dist: 0.4 + min_obstacle_dist: 0.35 inflation_dist: 0.5 #0.6 include_dynamic_obstacles: False include_costmap_obstacles: True # False -> 障害物割と無視 @@ -51,8 +51,8 @@ penalty_epsilon: 0.1 weight_max_vel_x: 1000 #2 weight_max_vel_theta: 1000 #1 - weight_acc_lim_x: 1 #100 #1 - weight_acc_lim_theta: 1 #1 + weight_acc_lim_x: 100 #100 #1 + weight_acc_lim_theta: 100 #1 weight_kinematics_nh: 1000 weight_kinematics_forward_drive: 100 #1 weight_kinematics_turning_radius: 1 @@ -64,7 +64,7 @@ selection_alternative_time_cost: False # not in use yet # Homotopy Class Planner - enable_homotopy_class_planning: False #True #軌道の複数代替案を計算するかどうか? + enable_homotopy_class_planning: False #軌道の複数代替案を計算するかどうか? enable_multithreading: False #True simple_exploration: False max_number_classes: 2 #4 軌道の代替案の計算個数 @@ -87,4 +87,4 @@ # ・no_inner_iterations, no_outer_iterations -> 小さく # ・weight_acc_lim -> 0.0に # ・enable_homotopy_class_planning -> False ※影響大 - # ・max_number_classes -> 小さく(2で十分?) \ No newline at end of file + # ・max_number_classes -> 小さく(2で十分?) diff --git a/src/tsukuba2022/rviz_cfg/nav.rviz b/src/tsukuba2022/rviz_cfg/nav.rviz new file mode 100644 index 0000000..408d490 --- /dev/null +++ b/src/tsukuba2022/rviz_cfg/nav.rviz @@ -0,0 +1,368 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 634 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Name: Time + SyncMode: 0 + SyncSource: LaserScan + - Class: orne_rviz_plugins/StateTriggerPanel + Name: StateTriggerPanel +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + hokuyo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_caster_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + left_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_caster_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + right_wheel: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + velodyne_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 0; 255; 0 + Color Transformer: FlatColor + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 170; 0; 0 + Min Color: 0; 85; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 5 + Size (m): 0.10000000149011612 + Style: Points + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 255; 25; 0 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Particles + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /particlecloud + Unreliable: false + Value: true + - Alpha: 1 + Class: rviz/Polygon + Color: 25; 255; 0 + Enabled: true + Name: Footprint + Queue Size: 10 + Topic: /move_base/local_costmap/footprint + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Global Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base/GlobalPlanner/plan + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.10000000149011612 + Name: Local Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /move_base/TrajectoryPlannerROS/local_plan + Unreliable: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: true + Name: GlobalCostmap + Topic: /move_base/global_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: LocalCostmap + Topic: /move_base/local_costmap/costmap + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Arrow Length: 0.30000001192092896 + Axes Length: 0.30000001192092896 + Axes Radius: 0.009999999776482582 + Class: rviz/PoseArray + Color: 0; 0; 127 + Enabled: true + Head Length: 0.07000000029802322 + Head Radius: 0.029999999329447746 + Name: Waypoints + Queue Size: 10 + Shaft Length: 0.23000000417232513 + Shaft Radius: 0.009999999776482582 + Shape: Arrow (Flat) + Topic: /waypoints + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 0; 0; 127 + Enabled: false + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /move_base_simple/goal + Unreliable: false + Value: false + - Alpha: 1 + Class: rviz/PointStamped + Color: 204; 41; 204 + Enabled: false + History Length: 10 + Name: PointStamped + Queue Size: 10 + Radius: 0.20000000298023224 + Topic: /target_point + Unreliable: false + Value: false + - Alpha: 1 + Class: rviz/PointStamped + Color: 239; 41; 41 + Enabled: false + History Length: 1 + Name: PointStamped + Queue Size: 10 + Radius: 0.4000000059604645 + Topic: /filtered_target_point + Unreliable: false + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 10 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/ThirdPersonFollower + Distance: 34.766265869140625 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -0.058651626110076904 + Y: 0.01184246689081192 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.5147963762283325 + Target Frame: base_link + Yaw: 3.1003947257995605 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 887 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001930000031cfc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e000002b7000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c01000002fb0000005f0000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d006501000000000000045000000000000000000000041c0000031c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + StateTriggerPanel: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1461 + X: 380 + Y: 0 diff --git a/src/tsukuba2022/rviz_cfg/record_waypoints.rviz b/src/tsukuba2022/rviz_cfg/record_waypoints.rviz new file mode 100644 index 0000000..659846c --- /dev/null +++ b/src/tsukuba2022/rviz_cfg/record_waypoints.rviz @@ -0,0 +1,240 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 418 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: LaserScan +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.699999988079071 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Unreliable: false + Use Timestamp: false + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_scan: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + caster_back_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + wheel_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wheel_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/LaserScan + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Min Color: 0; 0; 0 + Name: LaserScan + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.009999999776482582 + Style: Points + Topic: /scan + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/MarkerArray + Enabled: true + Marker Topic: /waypoints + Name: Waypoints + Namespaces: + {} + Queue Size: 100 + Value: true + - Alpha: 1 + Class: rviz/PointStamped + Color: 204; 41; 204 + Enabled: true + History Length: 1 + Name: PointStamped + Queue Size: 10 + Radius: 0.20000000298023224 + Topic: /clicked_point + Unreliable: false + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: Pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /move_base_simple/goal + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 10 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 9.116127014160156 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.7853981852531433 + Focal Point: + X: -0.43540072441101074 + Y: -0.04363036900758743 + Z: 0.47935307025909424 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 1.179796576499939 + Target Frame: + Yaw: 3.1354191303253174 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 716 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001560000022dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e0000022d000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000252fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000252000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b00000026c00fffffffb0000000800540069006d00650100000000000004500000000000000000000003540000022d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 195 + Y: 59 diff --git a/src/tsukuba2022/rviz_cfg/teb_nav.rviz b/src/tsukuba2022/rviz_cfg/teb_nav.rviz index a62c8a7..38bb6dc 100644 --- a/src/tsukuba2022/rviz_cfg/teb_nav.rviz +++ b/src/tsukuba2022/rviz_cfg/teb_nav.rviz @@ -5,7 +5,7 @@ Property Tree Widget: Expanded: ~ Splitter Ratio: 0.5 - Tree Height: 538 + Tree Height: 622 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -294,8 +294,7 @@ Marker Topic: /move_base/TebLocalPlannerROS/teb_markers Name: Teb Marker Namespaces: - PointObstacles: true - RobotFootprintModel: true + {} Queue Size: 100 Value: true - Alpha: 1 @@ -359,17 +358,17 @@ Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 1.5647963285446167 + Pitch: 1.054796576499939 Target Frame: base_link - Yaw: 3.135395050048828 + Yaw: 3.1103944778442383 Saved: ~ Window Geometry: Displays: collapsed: false - Height: 786 + Height: 877 Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd000000040000000000000193000002b7fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e00000257000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c010000029b0000005a0000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d0065010000000000000450000000000000000000000369000002b700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd00000004000000000000019300000312fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e000002ab000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c01000002ef000000610000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d00650100000000000004500000000000000000000003970000031200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false StateTriggerPanel: @@ -380,6 +379,6 @@ collapsed: false Views: collapsed: true - Width: 1282 - X: 217 - Y: 1 + Width: 1328 + X: 501 + Y: 19 diff --git a/src/tsukuba2022/urdf/igvc_robot.gazebo b/src/tsukuba2022/urdf/igvc_robot.gazebo deleted file mode 100644 index f32242a..0000000 --- a/src/tsukuba2022/urdf/igvc_robot.gazebo +++ /dev/null @@ -1,76 +0,0 @@ - - - - - - - - - igvc_robot/cmd_vel - igvc_robot/odom - base_link - odom - world - - true - false - false - - true - - true - - 30 - left_wheel_hinge - right_wheel_hinge - 0.670 - 0.192 - 1 - 10 - na - false - - - - - - - Gazebo/Black - - - - - 5.0 - 5.0 - 1000000.0 - 100.0 - 0.001 - 1.0 - - - - - 5.0 - 5.0 - 1000000.0 - 100.0 - 0.001 - 1.0 - - - - - 0.0 - 0.0 - - - - 0.0 - 0.0 - - - diff --git a/src/tsukuba2022/urdf/igvc_robot.xacro b/src/tsukuba2022/urdf/igvc_robot.xacro deleted file mode 100644 index bcf1d93..0000000 --- a/src/tsukuba2022/urdf/igvc_robot.xacro +++ /dev/null @@ -1,221 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - left_wheel - base_link - - - - - - - - - - - - - - - - - - - - - - - - - - - - right_wheel - base_link - - - - - - - - diff --git a/src/tsukuba2022/urdf/igvc_robot_cp.urdf b/src/tsukuba2022/urdf/igvc_robot_cp.urdf deleted file mode 100644 index 3ecfca1..0000000 --- a/src/tsukuba2022/urdf/igvc_robot_cp.urdf +++ /dev/null @@ -1,220 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - left_wheel - base_link - - - - - - - - - - - - - - - - - - - - - - - - - - - - right_wheel - base_link - - - - - - - transmission_interface/SimpleTransmission - - VelocityJointInterface - - - VelocityJointInterface - 1 - - - - - transmission_interface/SimpleTransmission - - VelocityJointInterface - - - VelocityJointInterface - 1 - - - diff --git a/src/tsukuba2022/urdf/orange2022.gazebo b/src/tsukuba2022/urdf/orange2022.gazebo index 5bd5d41..da23844 100644 --- a/src/tsukuba2022/urdf/orange2022.gazebo +++ b/src/tsukuba2022/urdf/orange2022.gazebo @@ -37,7 +37,7 @@ 1000000.0 100.0 0.001 - 3.0 + 1.0 @@ -47,7 +47,7 @@ 1000000.0 100.0 0.001 - 3.0 + 1.0 diff --git a/src/tsukuba2022/urdf/sensors/camera.urdf.xacro b/src/tsukuba2022/urdf/sensors/camera.urdf.xacro deleted file mode 100644 index 9326083..0000000 --- a/src/tsukuba2022/urdf/sensors/camera.urdf.xacro +++ /dev/null @@ -1,76 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 30.0 - - 0 0 0 0 ${PI/2} 0 - 3.1415 - - R8G8B8 - 800 - 800 - - - 0.01 - 100 - - - stereographic - 1 - 1.5707 - 512 - - - - - true - 0.0 - cv_camera - image_raw - camera_info - camera_link - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - 0.0 - - - Gazebo/DarkGray - - - - - - diff --git a/src/tsukuba2022/world/course.world b/src/tsukuba2022/world/course.world deleted file mode 100644 index 19db764..0000000 --- a/src/tsukuba2022/world/course.world +++ /dev/null @@ -1,232 +0,0 @@ - - - - - - 0 -30 60 0 1.1 1.5708 - - - - 0 - 1 - - - - model://sun - - - - model://course - 0 0 0 0 0 0 - Course - - - - model://ramp - 0 13.269552 0 0 0 1.570796 - Ramp1 - - - - - - - model://barricade - -19.1652 -17.2165 0 0 -0 -0.8 - Barricade 1 - - - model://barricade - 18.8846 -17.517 0 0 0 0.21445 - Barricade 2 - - - model://barricade - 9.57 12.3819 0 0 0 -0.30353 - Barricade 3 - - - model://barricade - -8.5858 12.1745 0 0 0 0.14831 - Barricade 4 - - - - - - - - model://construction_barrel - 14.8591 -15.356 0 0 -0 0 - Construction Barrel 1 - - - model://construction_barrel - 20.9235 -13.6107 -2e-06 -0 7e-06 -2e-06 - Construction Barrel 2 - - - model://construction_barrel - 17.1121 -9.439 -2e-06 -0 7e-06 -2e-06 - Construction Barrel 3 - - - model://construction_barrel - 18.2218 -9.1396 -2e-06 -0 7e-06 -2e-06 - Construction Barrel 4 - - - model://construction_barrel - 17.9234 -6.37453 -0 0 0 -8e-06 - Construction Barrel 5 - - - model://construction_barrel - 18.8232 -5.70024 1e-06 3e-06 2e-06 -1e-05 - Construction Barrel 6 - - - model://construction_barrel - 16.061 -4.40601 0 2e-06 0 -1.2e-05 - Construction Barrel 7 - - - model://construction_barrel - 18.100 1.30974 -0 0 0 -1.4e-05 - Construction Barrel 8 - - - model://construction_barrel - 17.4279 7.243 -1e-06 3e-06 -0 -2.3e-05 - Construction Barrel 9 - - - model://construction_barrel - 20.564 11.0036 0 1e-06 1e-06 -2.5e-05 - Construction Barrel 10 - - - model://construction_barrel - 17.6329 14.8412 -2e-06 7e-06 -2e-06 -2.6e-05 - Construction Barrel 11 - - - model://construction_barrel - 12.9292 12.123 -2e-06 7e-06 -2e-06 -2.7e-05 - Construction Barrel 12 - - - model://construction_barrel - 12.0142 16.9984 -0 0 -0 -2.8e-05 - Construction Barrel 13 - - - model://construction_barrel - 9.43968 17.4719 -2e-06 4e-06 7e-06 -2.9e-05 - Construction Barrel 14 - - - model://construction_barrel - 7.19005 17.3195 -2e-06 -7e-06 -4e-06 -3e-05 - Construction Barrel 15 - - - model://construction_barrel - 6.34524 13.0764 -0 0 0 -3.1e-05 - Construction Barrel 16 - - - model://construction_barrel - 3.73125 17.5897 -1e-06 3e-06 0 -3.2e-05 - Construction Barrel 17 - - - model://construction_barrel - 0.061325 16.9475 -1e-06 3e-06 -0 -3.4e-05 - Construction Barrel 18 - - - model://construction_barrel - -3.46882 16.9529 -2e-06 7e-06 -4e-06 -3.5e-05 - Construction Barrel 19 - - - model://construction_barrel - -6.95984 17.4552 -3e-06 -0 -1.2e-05 -3.6e-05 - Construction Barrel 20 - - - model://construction_barrel - -10.1446 16.9341 -0 0 -0 -3.7e-05 - Construction Barrel 21 - - - model://construction_barrel - -6.01782 12.36 1e-06 3e-06 2e-06 -3.8e-05 - Construction Barrel 22 - - - model://construction_barrel - -12.2652 12.7116 -2e-06 -7e-06 -4e-06 -4e-05 - Construction Barrel 23 - - - model://construction_barrel - -12.8712 16.2905 -4e-06 -5e-06 -7e-06 -4.1e-05 - Construction Barrel 24 - - - model://construction_barrel - -18.178 16.2268 -1e-06 0 5e-06 -4.2e-05 - Construction Barrel 25 - - - model://construction_barrel - -20.7988 10.4853 -0 0 0 -4.3e-05 - Construction Barrel 26 - - - model://construction_barrel - -18.397 8.225 -2e-06 7e-06 -2e-06 -4.4e-05 - Construction Barrel 27 - - - model://construction_barrel - -18.100 0.857426 1e-06 3e-06 2e-06 -4.6e-05 - Construction Barrel 28 - - - model://construction_barrel - -16.1784 -5.72593 1e-06 3e-06 2e-06 -4.7e-05 - Construction Barrel 29 - - - model://construction_barrel - -19.1376 -6.88455 0 0 0 -4.9e-05 - Construction Barrel 30 - - - model://construction_barrel - -20.0303 -6.42554 -2e-06 -7e-06 -4e-06 -4.9e-05 - Construction Barrel 31 - - - model://construction_barrel - -18.4685 -9.4751 -3e-06 -6e-06 -5e-06 -5.1e-05 - Construction Barrel 32 - - - model://construction_barrel - -17.3279 -9.55999 -2e-06 4e-06 7e-06 -5.1e-05 - Construction Barrel 33 - - - model://construction_barrel - -16.102 -15.2392 -0 0 0 -5.7e-05 - Construction Barrel 34 - - - - - - diff --git a/src/tsukuba2022/world/course_v2.world b/src/tsukuba2022/world/course_v2.world deleted file mode 100644 index b31e86f..0000000 --- a/src/tsukuba2022/world/course_v2.world +++ /dev/null @@ -1,255 +0,0 @@ - - - - - - 0 -30 60 0 1.1 1.5708 - - - - 0 - 1 - - - - model://sun - - - - model://course_v2 - 0 0 0 0 0 0 - Course - - - - model://ramp - 0 13.269552 0 0 0 1.570796 - Ramp1 - - - - - - - model://barricade - -19.1652 -17.2165 0 0 0 -0.8 - Barricade 1 - - - model://barricade - 18.8846 -17.517 0 0 0 0.21445 - Barricade 2 - - - model://barricade - 9.57 12.3819 0 0 0 0.30353 - Barricade 3 - - - model://barricade - -8.5858 12.1745 0 0 0 0.14831 - Barricade 4 - - - - - - - - model://construction_barrel - 14.8591 -15.356 0 0 0 0 - Construction Barrel 1 - - - model://construction_barrel - 20.9235 -13.6107 0 0 0 0 - Construction Barrel 2 - - - model://construction_barrel - 17.1121 -9.439 0 0 0 0 - Construction Barrel 3 - - - model://construction_barrel - 18.2218 -9.1396 0 0 0 0 - Construction Barrel 4 - - - model://construction_barrel - 17.9234 -6.37453 0 0 0 0 - Construction Barrel 5 - - - model://construction_barrel - 18.8232 -5.70024 0 0 0 0 - Construction Barrel 6 - - - model://construction_barrel - 16.061 -4.40601 0 0 0 0 - Construction Barrel 7 - - - model://construction_barrel - 18.100 1.30974 0 0 0 0 - Construction Barrel 8 - - - model://construction_barrel - 17.4279 7.243 0 0 0 0 - Construction Barrel 9 - - - model://construction_barrel - 20.564 11.0036 0 0 0 0 - Construction Barrel 10 - - - model://construction_barrel - 17.6292 14.470 0 0 0 0 - Construction Barrel 11 - - - model://construction_barrel - 12.9292 12.123 0 0 0 0 - Construction Barrel 12 - - - model://construction_barrel - 12.0142 16.9984 0 0 0 0 - Construction Barrel 13 - - - model://construction_barrel - 9.43968 17.4719 0 0 0 0 - Construction Barrel 14 - - - model://construction_barrel - 7.19005 17.3195 0 0 0 0 - Construction Barrel 15 - - - model://construction_barrel - 6.34524 13.0764 0 0 0 0 - Construction Barrel 16 - - - model://construction_barrel - 3.73125 17.5897 0 0 0 0 - Construction Barrel 17 - - - model://construction_barrel - 0.061325 16.9475 0 0 0 0 - Construction Barrel 18 - - - model://construction_barrel - -3.46882 16.9529 0 0 0 0 - Construction Barrel 19 - - - model://construction_barrel - -6.95984 17.4552 0 0 0 0 - Construction Barrel 20 - - - model://construction_barrel - -10.1446 16.9341 0 0 0 0 - Construction Barrel 21 - - - model://construction_barrel - -6.01782 12.36 0 0 0 0 - Construction Barrel 22 - - - model://construction_barrel - -12.2652 12.7116 0 0 0 0 - Construction Barrel 23 - - - model://construction_barrel - -12.8712 16.2905 0 0 0 0 - Construction Barrel 24 - - - model://construction_barrel - -18.178 16.2268 0 0 0 0 - Construction Barrel 25 - - - model://construction_barrel - -20.7988 10.4853 0 0 0 0 - Construction Barrel 26 - - - model://construction_barrel - -18.397 8.225 0 0 0 0 - Construction Barrel 27 - - - model://construction_barrel - -17.2492 0.7495 0 0 0 0 - Construction Barrel 28 - - - model://construction_barrel - -16.1784 -5.72593 0 0 0 0 - Construction Barrel 29 - - - model://construction_barrel - -19.1376 -6.88455 0 0 0 0 - Construction Barrel 30 - - - model://construction_barrel - -20.0303 -6.42554 0 0 0 0 - Construction Barrel 31 - - - model://construction_barrel - -18.4685 -9.4751 0 0 0 0 - Construction Barrel 32 - - - model://construction_barrel - -17.3279 -9.55999 0 0 0 0 - Construction Barrel 33 - - - model://construction_barrel - -16.102 -15.2392 0 0 0 0 - Construction Barrel 34 - - - - - - - diff --git a/src/turtlebot3/ISSUE_TEMPLATE.md b/src/turtlebot3/ISSUE_TEMPLATE.md deleted file mode 100644 index c36cfc2..0000000 --- a/src/turtlebot3/ISSUE_TEMPLATE.md +++ /dev/null @@ -1,57 +0,0 @@ -ISSUE TEMPLATE ver. 0.4.0 - -1. Which TurtleBot3 platform do you use? - - - [ ] Burger - - [ ] Waffle - - [ ] Waffle Pi - -2. Which ROS is working with TurtleBot3? - - - [ ] ROS 1 Kinetic Kame - - [ ] ROS 1 Melodic Morenia - - [ ] ROS 1 Noetic Ninjemys - - [ ] ROS 2 Dashing Diademata - - [ ] ROS 2 Eloquent Elusor - - [ ] ROS 2 Foxy Fitzroy - - [ ] etc (Please specify your ROS Version here) - -3. Which SBC(Single Board Computer) is working on TurtleBot3? - - - [ ] Intel Joule 570x - - [ ] Raspberry Pi 3B+ - - [ ] Raspberry Pi 4 - - [ ] etc (Please specify your SBC here) - -4. Which OS you installed on SBC? - - - [ ] Raspbian distributed by ROBOTIS - - [ ] Ubuntu MATE (16.04/18.04/20.04) - - [ ] Ubuntu preinstalled server (18.04/20.04) - - [ ] etc (Please specify your OS here) - -5. Which OS you installed on Remote PC? - - - [ ] Ubuntu 16.04 LTS (Xenial Xerus) - - [ ] Ubuntu 18.04 LTS (Bionic Beaver) - - [ ] Ubuntu 20.04 LTS (Focal Fossa) - - [ ] Windows 10 - - [ ] MAC OS X (Specify version) - - [ ] etc (Please specify your OS here) - -6. Specify the software and firmware version(Can be found from Bringup messages) - - - Software version: [x.x.x] - - Firmware version: [x.x.x] - -7. Specify the commands or instructions to reproduce the issue. - - - HERE - -8. Copy and Paste the error messages on terminal. - - - HERE - -9. Please describe the issue in detail. - - - HERE diff --git a/src/turtlebot3/LICENSE b/src/turtlebot3/LICENSE deleted file mode 100644 index 8dada3e..0000000 --- a/src/turtlebot3/LICENSE +++ /dev/null @@ -1,201 +0,0 @@ - Apache License - Version 2.0, January 2004 - http://www.apache.org/licenses/ - - TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION - - 1. Definitions. - - "License" shall mean the terms and conditions for use, reproduction, - and distribution as defined by Sections 1 through 9 of this document. - - "Licensor" shall mean the copyright owner or entity authorized by - the copyright owner that is granting the License. - - "Legal Entity" shall mean the union of the acting entity and all - other entities that control, are controlled by, or are under common - control with that entity. For the purposes of this definition, - "control" means (i) the power, direct or indirect, to cause the - direction or management of such entity, whether by contract or - otherwise, or (ii) ownership of fifty percent (50%) or more of the - outstanding shares, or (iii) beneficial ownership of such entity. - - "You" (or "Your") shall mean an individual or Legal Entity - exercising permissions granted by this License. - - "Source" form shall mean the preferred form for making modifications, - including but not limited to software source code, documentation - source, and configuration files. - - "Object" form shall mean any form resulting from mechanical - transformation or translation of a Source form, including but - not limited to compiled object code, generated documentation, - and conversions to other media types. - - "Work" shall mean the work of authorship, whether in Source or - Object form, made available under the License, as indicated by a - copyright notice that is included in or attached to the work - (an example is provided in the Appendix below). - - "Derivative Works" shall mean any work, whether in Source or Object - form, that is based on (or derived from) the Work and for which the - editorial revisions, annotations, elaborations, or other modifications - represent, as a whole, an original work of authorship. For the purposes - of this License, Derivative Works shall not include works that remain - separable from, or merely link (or bind by name) to the interfaces of, - the Work and Derivative Works thereof. - - "Contribution" shall mean any work of authorship, including - the original version of the Work and any modifications or additions - to that Work or Derivative Works thereof, that is intentionally - submitted to Licensor for inclusion in the Work by the copyright owner - or by an individual or Legal Entity authorized to submit on behalf of - the copyright owner. For the purposes of this definition, "submitted" - means any form of electronic, verbal, or written communication sent - to the Licensor or its representatives, including but not limited to - communication on electronic mailing lists, source code control systems, - and issue tracking systems that are managed by, or on behalf of, the - Licensor for the purpose of discussing and improving the Work, but - excluding communication that is conspicuously marked or otherwise - designated in writing by the copyright owner as "Not a Contribution." - - "Contributor" shall mean Licensor and any individual or Legal Entity - on behalf of whom a Contribution has been received by Licensor and - subsequently incorporated within the Work. - - 2. Grant of Copyright License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - copyright license to reproduce, prepare Derivative Works of, - publicly display, publicly perform, sublicense, and distribute the - Work and such Derivative Works in Source or Object form. - - 3. Grant of Patent License. Subject to the terms and conditions of - this License, each Contributor hereby grants to You a perpetual, - worldwide, non-exclusive, no-charge, royalty-free, irrevocable - (except as stated in this section) patent license to make, have made, - use, offer to sell, sell, import, and otherwise transfer the Work, - where such license applies only to those patent claims licensable - by such Contributor that are necessarily infringed by their - Contribution(s) alone or by combination of their Contribution(s) - with the Work to which such Contribution(s) was submitted. If You - institute patent litigation against any entity (including a - cross-claim or counterclaim in a lawsuit) alleging that the Work - or a Contribution incorporated within the Work constitutes direct - or contributory patent infringement, then any patent licenses - granted to You under this License for that Work shall terminate - as of the date such litigation is filed. - - 4. Redistribution. You may reproduce and distribute copies of the - Work or Derivative Works thereof in any medium, with or without - modifications, and in Source or Object form, provided that You - meet the following conditions: - - (a) You must give any other recipients of the Work or - Derivative Works a copy of this License; and - - (b) You must cause any modified files to carry prominent notices - stating that You changed the files; and - - (c) You must retain, in the Source form of any Derivative Works - that You distribute, all copyright, patent, trademark, and - attribution notices from the Source form of the Work, - excluding those notices that do not pertain to any part of - the Derivative Works; and - - (d) If the Work includes a "NOTICE" text file as part of its - distribution, then any Derivative Works that You distribute must - include a readable copy of the attribution notices contained - within such NOTICE file, excluding those notices that do not - pertain to any part of the Derivative Works, in at least one - of the following places: within a NOTICE text file distributed - as part of the Derivative Works; within the Source form or - documentation, if provided along with the Derivative Works; or, - within a display generated by the Derivative Works, if and - wherever such third-party notices normally appear. The contents - of the NOTICE file are for informational purposes only and - do not modify the License. You may add Your own attribution - notices within Derivative Works that You distribute, alongside - or as an addendum to the NOTICE text from the Work, provided - that such additional attribution notices cannot be construed - as modifying the License. - - You may add Your own copyright statement to Your modifications and - may provide additional or different license terms and conditions - for use, reproduction, or distribution of Your modifications, or - for any such Derivative Works as a whole, provided Your use, - reproduction, and distribution of the Work otherwise complies with - the conditions stated in this License. - - 5. Submission of Contributions. Unless You explicitly state otherwise, - any Contribution intentionally submitted for inclusion in the Work - by You to the Licensor shall be under the terms and conditions of - this License, without any additional terms or conditions. - Notwithstanding the above, nothing herein shall supersede or modify - the terms of any separate license agreement you may have executed - with Licensor regarding such Contributions. - - 6. Trademarks. This License does not grant permission to use the trade - names, trademarks, service marks, or product names of the Licensor, - except as required for reasonable and customary use in describing the - origin of the Work and reproducing the content of the NOTICE file. - - 7. Disclaimer of Warranty. Unless required by applicable law or - agreed to in writing, Licensor provides the Work (and each - Contributor provides its Contributions) on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or - implied, including, without limitation, any warranties or conditions - of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A - PARTICULAR PURPOSE. You are solely responsible for determining the - appropriateness of using or redistributing the Work and assume any - risks associated with Your exercise of permissions under this License. - - 8. Limitation of Liability. In no event and under no legal theory, - whether in tort (including negligence), contract, or otherwise, - unless required by applicable law (such as deliberate and grossly - negligent acts) or agreed to in writing, shall any Contributor be - liable to You for damages, including any direct, indirect, special, - incidental, or consequential damages of any character arising as a - result of this License or out of the use or inability to use the - Work (including but not limited to damages for loss of goodwill, - work stoppage, computer failure or malfunction, or any and all - other commercial damages or losses), even if such Contributor - has been advised of the possibility of such damages. - - 9. Accepting Warranty or Additional Liability. While redistributing - the Work or Derivative Works thereof, You may choose to offer, - and charge a fee for, acceptance of support, warranty, indemnity, - or other liability obligations and/or rights consistent with this - License. However, in accepting such obligations, You may act only - on Your own behalf and on Your sole responsibility, not on behalf - of any other Contributor, and only if You agree to indemnify, - defend, and hold each Contributor harmless for any liability - incurred by, or claims asserted against, such Contributor by reason - of your accepting any such warranty or additional liability. - - END OF TERMS AND CONDITIONS - - APPENDIX: How to apply the Apache License to your work. - - To apply the Apache License to your work, attach the following - boilerplate notice, with the fields enclosed by brackets "{}" - replaced with your own identifying information. (Don't include - the brackets!) The text should be enclosed in the appropriate - comment syntax for the file format. We also recommend that a - file or class name and description of purpose be included on the - same "printed page" as the copyright notice for easier - identification within third-party archives. - - Copyright {yyyy} {name of copyright owner} - - Licensed under the Apache License, Version 2.0 (the "License"); - you may not use this file except in compliance with the License. - You may obtain a copy of the License at - - http://www.apache.org/licenses/LICENSE-2.0 - - Unless required by applicable law or agreed to in writing, software - distributed under the License is distributed on an "AS IS" BASIS, - WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - See the License for the specific language governing permissions and - limitations under the License. diff --git a/src/turtlebot3/README.md b/src/turtlebot3/README.md deleted file mode 100644 index 6febf35..0000000 --- a/src/turtlebot3/README.md +++ /dev/null @@ -1,53 +0,0 @@ -# TurtleBot3 - - -[![kinetic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/kinetic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/kinetic-devel) - -[![melodic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/melodic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/melodic-devel) - -[![noetic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/noetic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/noetic-devel) - -[![dashing-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/dashing-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/dashing-devel) - -[![foxy-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/foxy-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/foxy-devel) - -[![galactic-devel Status](https://github.com/ROBOTIS-GIT/turtlebot3/workflows/galactic-devel/badge.svg)](https://github.com/ROBOTIS-GIT/turtlebot3/tree/galactic-devel) - -## ROBOTIS e-Manual for TurtleBot3 -- [ROBOTIS e-Manual for TurtleBot3](http://turtlebot3.robotis.com/) - -## Wiki for turtlebot3 Packages -- http://wiki.ros.org/turtlebot3 (metapackage) -- http://wiki.ros.org/turtlebot3_bringup -- http://wiki.ros.org/turtlebot3_description -- http://wiki.ros.org/turtlebot3_example -- http://wiki.ros.org/turtlebot3_navigation -- http://wiki.ros.org/turtlebot3_slam -- http://wiki.ros.org/turtlebot3_teleop - -## Open Source related to TurtleBot3 -- [turtlebot3](https://github.com/ROBOTIS-GIT/turtlebot3) -- [turtlebot3_msgs](https://github.com/ROBOTIS-GIT/turtlebot3_msgs) -- [turtlebot3_simulations](https://github.com/ROBOTIS-GIT/turtlebot3_simulations) -- [turtlebot3_applications_msgs](https://github.com/ROBOTIS-GIT/turtlebot3_applications_msgs) -- [turtlebot3_applications](https://github.com/ROBOTIS-GIT/turtlebot3_applications) -- [turtlebot3_autorace](https://github.com/ROBOTIS-GIT/turtlebot3_autorace) -- [turtlebot3_deliver](https://github.com/ROBOTIS-GIT/turtlebot3_deliver) -- [hls_lfcd_lds_driver](https://github.com/ROBOTIS-GIT/hls_lfcd_lds_driver) -- [turtlebot3_manipulation](https://github.com/ROBOTIS-GIT/turtlebot3_manipulation.git) -- [turtlebot3_manipulation_simulations](https://github.com/ROBOTIS-GIT/turtlebot3_manipulation_simulations.git) -- [open_manipulator_msgs](https://github.com/ROBOTIS-GIT/open_manipulator_msgs) -- [open_manipulator](https://github.com/ROBOTIS-GIT/open_manipulator) -- [open_manipulator_simulations](https://github.com/ROBOTIS-GIT/open_manipulator_simulations) -- [open_manipulator_perceptions](https://github.com/ROBOTIS-GIT/open_manipulator_perceptions) -- [dynamixel_sdk](https://github.com/ROBOTIS-GIT/DynamixelSDK) -- [OpenCR-Hardware](https://github.com/ROBOTIS-GIT/OpenCR-Hardware) -- [OpenCR](https://github.com/ROBOTIS-GIT/OpenCR) - -## Documents and Videos related to TurtleBot3 -- [ROBOTIS e-Manual for TurtleBot3](http://turtlebot3.robotis.com/) -- [ROBOTIS e-Manual for OpenManipulator](http://emanual.robotis.com/docs/en/platform/openmanipulator/) -- [ROBOTIS e-Manual for Dynamixel SDK](http://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/overview/) -- [Website for TurtleBot Series](http://www.turtlebot.com/) -- [e-Book for TurtleBot3](https://community.robotsource.org/t/download-the-ros-robot-programming-book-for-free/51/) -- [Videos for TurtleBot3 ](https://www.youtube.com/playlist?list=PLRG6WP3c31_XI3wlvHlx2Mp8BYqgqDURU) diff --git a/src/turtlebot3/turtlebot3/CHANGELOG.rst b/src/turtlebot3/turtlebot3/CHANGELOG.rst deleted file mode 100644 index 7a5e478..0000000 --- a/src/turtlebot3/turtlebot3/CHANGELOG.rst +++ /dev/null @@ -1,155 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package turtlebot3 -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.2.6 (2022-02-24) ------------------- -* add LDS-02 support -* Use OpenCV for Picam(Noetic only) -* Fix teleop_key on Windows 10 -* Contributors: Rushikesh Kamalapurkar, Ashe Kim, Will Son - -1.2.5 (2020-12-30) ------------------- -* Python 2/3 compatibility fix -* Rectify IMU update rate to 0 on Gazebo -* Contributors: Sean Yen, PinkDraconian - -1.2.4 (2020-09-29) ------------------- -* Package info updated -* Contributors: Will Son - -1.2.3 (2020-03-03) ------------------- -* Updated inertial data in turtlebot3_waffle_for_open_manipulator.urdf.xacro, turtlebot3_waffle_pi_for_open_manipulator.urdf.xacro -* Added turtlebot3_manipulation_slam.launch for TurtleBot3 SLAM with OpenMANIPULATOR -* Contributors: Ryan Shim, Will Son - -1.2.2 (2019-08-20) ------------------- -* Fixed `dwa local planner params` for dwa_local_planner 1.16.2 `#415 `_ -* This patch only applies to ROS 1 Melodic. -* Contributors: atinfinity, Kayman - -1.2.1 (2019-08-20) ------------------- -* Fixed typo `#436 `_ -* Fixed ROS_ASSERT bug `#416 `_ -* Deleted '/' to sync tf2 `#402 `_ -* Added turtlebot3_remote.launch to turtlebot3_model.launch `#389 `_ -* Contributors: Jonathan Hechtbauer, Pallav Bhalla, ant, Ryan Shim, Kayman, Darby Lim, Gilbert, Pyo - -1.2.0 (2019-01-22) ------------------- -* changed math.ceil() operation `#373 `_ -* fixed TypeError integers -* fixed read of scanned samples when there isn't 360 -* updated map.yaml `#348 `_ -* added an additional argument move_forward_only to prohibit backward locomotion in navigation `#339 `_ -* fixed typo `#280 `_ -* added windows port `#358 `_ -* Contributors: Gilbert, Darby Lim, linzhibo, oiz5201618, yoshimalucky, Steven Macenski, Eduardo Avelar, Sean Yen, Pyo - -1.1.0 (2018-07-23) ------------------- -* added bringup to load multiple robot simply #251 -* added arguments for multiple robot -* added odometrySource -* modified camera topic name -* modified base_scan update_rate and add param on diff_drive #258 -* modified the laser scanner update_rate in the gazebo xacro files #258 -* modified origin of collision in Waffle URDF -* updated turtlebot3_diagnostic node -* updated firmware version from 1.2.0 to 1.2.2 -* updated get firmware version -* updated version check function -* updated warn msg for version check -* deleted unused get_scan function #227 -* Contributors: Darby Lim, Gilbert, Eduardo Avelar, shtseng, Pyo - -1.0.0 (2018-05-29) ------------------- -* added cartographer -* added hector mapping -* added karto SLAM -* added frontier_exploration -* added launch files to run various SLAMs -* added robot model for OpenManipulator and turtlebot3_autorace -* added exec python nodes like marker_server in catkin_install_python -* added frameName for imu on gazebo (however, there is no effect.) -* added variable to check version only once (turtlebot3_bringup) -* modified global names `#211 `_ from FurqanHabibi/fix_global_topic_name -* modified gmapping parameters -* modified navigation parameters -* modified version check and firmware version (turtlebot3_bringup) -* modified robot names -* modified range of lidar, lidar position, scan param -* modified camera position and fixed slip bug -* modified waffle_pi stl files -* modified initial value, profile function, limit velocity msg (teleop) -* merged pull request `#154 `_ `#153 `_ `#148 `_ `#147 `_ `#146 `_ `#145 `_ -* Contributors: Darby Lim, Leon Jung, Gilbert, KurtE, ncnynl, FurqanHabibi, skasperski, ihadzic, Pyo - -0.2.1 (2018-03-14) ------------------- -* added install directory -* refactoring for release -* Contributors: Pyo - -0.2.0 (2018-03-12) ------------------- -* added turtlebot3_rpicamera.launch for raspberry pi camera -* added waffle pi model (urdf and gazebo) -* added verion check function -* added diagnostics node -* added scripts for reload rules -* added example package -* modified firmware version -* modified param config -* modified topic of gazebo plugin -* modified r200 tf tree -* modified gazebo imu link -* removed the large bag file and added download command from other site -* refactoring for release -* Contributors: Darby Lim, Gilbert, Leon Jung, Pyo - -0.1.6 (2017-08-14) ------------------- -* fixed typo -* fixed xacro.py deprecation -* modified file location -* updated nav param -* updated SLAM param -* updated model.launch -* updated IMU link -* updated gazebo config -* Contributors: Darby Lim, Hunter L. Allen - -0.1.5 (2017-05-25) ------------------- -* updated turtlebot3 waffle URDF -* changed the node name from hlds_laser_publisher to turtlebot3_lds -* modified bag and map files -* added SLAM bag file -* Contributors: Darby Lim, Pyo - -0.1.4 (2017-05-23) ------------------- -* modified launch file name -* added teleop package -* Contributors: Darby Lim - -0.1.3 (2017-04-24) ------------------- -* Detached turtlebot3_msgs package from turtlebot3 package for uploading to rosdistro -* modified the package information for release -* modified SLAM param -* modified the description, authors, depend option and delete the core package -* modified the turtlebot bringup files -* modified pkg setting for turtlebot3_core -* modified the navigation package and turtlebot3 node for demo -* modified the wheel speed gain -* added Intel RealSense R200 -* added LDS sensor -* Contributors: Darby Lim, Leon Jung, Pyo diff --git a/src/turtlebot3/turtlebot3/CMakeLists.txt b/src/turtlebot3/turtlebot3/CMakeLists.txt deleted file mode 100644 index 64469eb..0000000 --- a/src/turtlebot3/turtlebot3/CMakeLists.txt +++ /dev/null @@ -1,4 +0,0 @@ -cmake_minimum_required(VERSION 3.0.2) -project(turtlebot3) -find_package(catkin REQUIRED) -catkin_metapackage() diff --git a/src/turtlebot3/turtlebot3/package.xml b/src/turtlebot3/turtlebot3/package.xml deleted file mode 100644 index e766173..0000000 --- a/src/turtlebot3/turtlebot3/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - turtlebot3 - 1.2.6 - - ROS packages for the Turtlebot3 (meta package) - - Apache 2.0 - BSD - Pyo - Darby Lim - Gilbert - HanCheol Cho - Ashe Kim - Leon Jung - Will Son - http://wiki.ros.org/turtlebot3 - http://turtlebot3.robotis.com - https://github.com/ROBOTIS-GIT/turtlebot3 - https://github.com/ROBOTIS-GIT/turtlebot3/issues - catkin - turtlebot3_bringup - turtlebot3_description - turtlebot3_example - turtlebot3_navigation - turtlebot3_slam - turtlebot3_teleop - - diff --git a/src/turtlebot3/turtlebot3_teleop/CHANGELOG.rst b/src/turtlebot3/turtlebot3_teleop/CHANGELOG.rst deleted file mode 100644 index d266a37..0000000 --- a/src/turtlebot3/turtlebot3_teleop/CHANGELOG.rst +++ /dev/null @@ -1,73 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package turtlebot3_teleop -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.2.6 (2022-02-24) ------------------- -* Fix teleop_key on Windows 10 -* Contributors: Rushikesh Kamalapurkar - -1.2.5 (2020-12-30) ------------------- -* Python 2/3 compatibility fix -* Contributors: Sean Yen - -1.2.4 (2020-09-29) ------------------- -* Package info updated -* Contributors: Will Son - -1.2.3 (2020-03-03) ------------------- -* none - -1.2.2 (2019-08-20) ------------------- -* none - -1.2.1 (2019-08-20) ------------------- -* none - -1.2.0 (2019-01-22) ------------------- -* added windows port `#358 `_ -* Contributors: Sean Yen, Taehun Lim - -1.1.0 (2018-07-23) ------------------- -* none - -1.0.0 (2018-05-29) ------------------- -* added constrain to limit velocity -* modified initial value, profile function, limit velocity msg -* modified global names `#211 `_ from FurqanHabibi/fix_global_topic_name -* Contributors: Darby Lim, Muhammad Furqan Habibi, Pyo - -0.2.1 (2018-03-14) ------------------- -* none - -0.2.0 (2018-03-12) ------------------- -* refactoring for release -* Contributors: Pyo - -0.1.6 (2017-08-14) ------------------- -* none - -0.1.5 (2017-05-25) ------------------- -* none - -0.1.4 (2017-05-23) ------------------- -* modified launch file name -* added teleop package -* Contributors: Darby Lim - -0.1.3 (2017-04-24) ------------------- -* none diff --git a/src/turtlebot3/turtlebot3_teleop/CMakeLists.txt b/src/turtlebot3/turtlebot3_teleop/CMakeLists.txt deleted file mode 100644 index 48a5b1e..0000000 --- a/src/turtlebot3/turtlebot3_teleop/CMakeLists.txt +++ /dev/null @@ -1,53 +0,0 @@ -################################################################################ -# Set minimum required version of cmake, project name and compile options -################################################################################ -cmake_minimum_required(VERSION 3.0.2) -project(turtlebot3_teleop) - -################################################################################ -# Find catkin packages and libraries for catkin and system dependencies -################################################################################ -find_package(catkin REQUIRED COMPONENTS - rospy - geometry_msgs -) - -################################################################################ -# Setup for python modules and scripts -################################################################################ -catkin_python_setup() - -################################################################################ -# Declare ROS messages, services and actions -################################################################################ - -################################################################################ -# Declare ROS dynamic reconfigure parameters -################################################################################ - -################################################################################ -# Declare catkin specific configuration to be passed to dependent projects -################################################################################ -catkin_package( - CATKIN_DEPENDS rospy geometry_msgs -) - -################################################################################ -# Build -################################################################################ - -################################################################################ -# Install -################################################################################ -catkin_install_python(PROGRAMS - nodes/turtlebot3_teleop_key - DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) - -install(DIRECTORY launch - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - -################################################################################ -# Test -################################################################################ diff --git a/src/turtlebot3/turtlebot3_teleop/launch/turtlebot3_teleop_key.launch b/src/turtlebot3/turtlebot3_teleop/launch/turtlebot3_teleop_key.launch deleted file mode 100644 index b6753ab..0000000 --- a/src/turtlebot3/turtlebot3_teleop/launch/turtlebot3_teleop_key.launch +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/src/turtlebot3/turtlebot3_teleop/nodes/turtlebot3_teleop_key b/src/turtlebot3/turtlebot3_teleop/nodes/turtlebot3_teleop_key deleted file mode 100755 index f6b5d7d..0000000 --- a/src/turtlebot3/turtlebot3_teleop/nodes/turtlebot3_teleop_key +++ /dev/null @@ -1,202 +0,0 @@ -#!/usr/bin/env python - -# Copyright (c) 2011, Willow Garage, Inc. -# All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions are met: -# -# * Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# * Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in the -# documentation and/or other materials provided with the distribution. -# * Neither the name of the Willow Garage, Inc. nor the names of its -# contributors may be used to endorse or promote products derived from -# this software without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. - -import rospy -from geometry_msgs.msg import Twist -import sys, select, os -if os.name == 'nt': - import msvcrt, time -else: - import tty, termios - -BURGER_MAX_LIN_VEL = 1.6 -BURGER_MAX_ANG_VEL = 2.84 - -WAFFLE_MAX_LIN_VEL = 0.26 -WAFFLE_MAX_ANG_VEL = 1.82 - -LIN_VEL_STEP_SIZE = 0.1 -ANG_VEL_STEP_SIZE = 0.1 - -msg = """ -Control Your TurtleBot3! ---------------------------- -Moving around: - w - a s d - x - -w/x : increase/decrease linear velocity (Burger : ~ 0.22, Waffle and Waffle Pi : ~ 0.26) -a/d : increase/decrease angular velocity (Burger : ~ 2.84, Waffle and Waffle Pi : ~ 1.82) - -space key, s : force stop - -CTRL-C to quit -""" - -e = """ -Communications Failed -""" - -def getKey(): - if os.name == 'nt': - timeout = 0.1 - startTime = time.time() - while(1): - if msvcrt.kbhit(): - if sys.version_info[0] >= 3: - return msvcrt.getch().decode() - else: - return msvcrt.getch() - elif time.time() - startTime > timeout: - return '' - - tty.setraw(sys.stdin.fileno()) - rlist, _, _ = select.select([sys.stdin], [], [], 0.1) - if rlist: - key = sys.stdin.read(1) - else: - key = '' - - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) - return key - -def vels(target_linear_vel, target_angular_vel): - return "currently:\tlinear vel %s\t angular vel %s " % (target_linear_vel,target_angular_vel) - -def makeSimpleProfile(output, input, slop): - if input > output: - output = min( input, output + slop ) - elif input < output: - output = max( input, output - slop ) - else: - output = input - - return output - -def constrain(input, low, high): - if input < low: - input = low - elif input > high: - input = high - else: - input = input - - return input - -def checkLinearLimitVelocity(vel): - if turtlebot3_model == "burger": - vel = constrain(vel, -BURGER_MAX_LIN_VEL, BURGER_MAX_LIN_VEL) - elif turtlebot3_model == "waffle" or turtlebot3_model == "waffle_pi": - vel = constrain(vel, -WAFFLE_MAX_LIN_VEL, WAFFLE_MAX_LIN_VEL) - else: - vel = constrain(vel, -BURGER_MAX_LIN_VEL, BURGER_MAX_LIN_VEL) - - return vel - -def checkAngularLimitVelocity(vel): - if turtlebot3_model == "burger": - vel = constrain(vel, -BURGER_MAX_ANG_VEL, BURGER_MAX_ANG_VEL) - elif turtlebot3_model == "waffle" or turtlebot3_model == "waffle_pi": - vel = constrain(vel, -WAFFLE_MAX_ANG_VEL, WAFFLE_MAX_ANG_VEL) - else: - vel = constrain(vel, -BURGER_MAX_ANG_VEL, BURGER_MAX_ANG_VEL) - - return vel - -if __name__=="__main__": - if os.name != 'nt': - settings = termios.tcgetattr(sys.stdin) - - rospy.init_node('turtlebot3_teleop') - pub = rospy.Publisher('cmd_vel', Twist, queue_size=10) - - turtlebot3_model = rospy.get_param("model", "burger") - - status = 0 - target_linear_vel = 0.0 - target_angular_vel = 0.0 - control_linear_vel = 0.0 - control_angular_vel = 0.0 - - try: - print(msg) - while not rospy.is_shutdown(): - key = getKey() - if key == 'w' : - target_linear_vel = checkLinearLimitVelocity(target_linear_vel + LIN_VEL_STEP_SIZE) - status = status + 1 - print(vels(target_linear_vel,target_angular_vel)) - elif key == 'x' : - target_linear_vel = checkLinearLimitVelocity(target_linear_vel - LIN_VEL_STEP_SIZE) - status = status + 1 - print(vels(target_linear_vel,target_angular_vel)) - elif key == 'a' : - target_angular_vel = checkAngularLimitVelocity(target_angular_vel + ANG_VEL_STEP_SIZE) - status = status + 1 - print(vels(target_linear_vel,target_angular_vel)) - elif key == 'd' : - target_angular_vel = checkAngularLimitVelocity(target_angular_vel - ANG_VEL_STEP_SIZE) - status = status + 1 - print(vels(target_linear_vel,target_angular_vel)) - elif key == ' ' or key == 's' : - target_linear_vel = 0.0 - control_linear_vel = 0.0 - target_angular_vel = 0.0 - control_angular_vel = 0.0 - print(vels(target_linear_vel, target_angular_vel)) - else: - if (key == '\x03'): - break - - if status == 20 : - print(msg) - status = 0 - - twist = Twist() - - control_linear_vel = makeSimpleProfile(control_linear_vel, target_linear_vel, (LIN_VEL_STEP_SIZE/2.0)) - twist.linear.x = control_linear_vel; twist.linear.y = 0.0; twist.linear.z = 0.0 - - control_angular_vel = makeSimpleProfile(control_angular_vel, target_angular_vel, (ANG_VEL_STEP_SIZE/2.0)) - twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = control_angular_vel - - pub.publish(twist) - - except: - print(e) - - finally: - twist = Twist() - twist.linear.x = 0.0; twist.linear.y = 0.0; twist.linear.z = 0.0 - twist.angular.x = 0.0; twist.angular.y = 0.0; twist.angular.z = 0.0 - pub.publish(twist) - - if os.name != 'nt': - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) diff --git a/src/turtlebot3/turtlebot3_teleop/package.xml b/src/turtlebot3/turtlebot3_teleop/package.xml deleted file mode 100644 index 5deb078..0000000 --- a/src/turtlebot3/turtlebot3_teleop/package.xml +++ /dev/null @@ -1,20 +0,0 @@ - - - turtlebot3_teleop - 1.2.6 - - Provides teleoperation using keyboard for TurtleBot3. - - BSD - Melonee Wise - Darby Lim - Pyo - Will Son - http://wiki.ros.org/turtlebot3_teleop - http://turtlebot3.robotis.com - https://github.com/ROBOTIS-GIT/turtlebot3 - https://github.com/ROBOTIS-GIT/turtlebot3/issues - catkin - rospy - geometry_msgs - diff --git a/src/turtlebot3/turtlebot3_teleop/setup.py b/src/turtlebot3/turtlebot3_teleop/setup.py deleted file mode 100644 index 0621677..0000000 --- a/src/turtlebot3/turtlebot3_teleop/setup.py +++ /dev/null @@ -1,12 +0,0 @@ -## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD - -from distutils.core import setup -from catkin_pkg.python_setup import generate_distutils_setup - -# fetch values from package.xml -setup_args = generate_distutils_setup( - packages=['turtlebot3_teleop'], - package_dir={'': 'src'} -) - -setup(**setup_args) diff --git a/src/turtlebot3/turtlebot3_teleop/src/turtlebot3_teleop/__init__.py b/src/turtlebot3/turtlebot3_teleop/src/turtlebot3_teleop/__init__.py deleted file mode 100644 index e69de29..0000000 --- a/src/turtlebot3/turtlebot3_teleop/src/turtlebot3_teleop/__init__.py +++ /dev/null diff --git a/src/velodyne/.github/ISSUE_TEMPLATE/bug_report.md b/src/velodyne/.github/ISSUE_TEMPLATE/bug_report.md deleted file mode 100644 index eb7f0f2..0000000 --- a/src/velodyne/.github/ISSUE_TEMPLATE/bug_report.md +++ /dev/null @@ -1,30 +0,0 @@ ---- -name: Bug report -about: Create a report to help us improve -title: '' -labels: bug -assignees: JWhitleyAStuff - ---- - -**Please complete the following information:** - - OS and Version: [e.g. Ubuntu 16.04] - - ROS Version: [e.g. Kinetic] - - Built from Source or Downloaded from Official Repository: - - Version: [if from repository, give version from `sudo dpkg -s ros-$ROS_VERSION-velodyne`, if from source, give commit hash] - -**Describe the bug** -A clear and concise description of what the bug is. - -**To Reproduce** -Steps to reproduce the behavior: -1. Go to '...' -2. Click on '....' -3. Scroll down to '....' -4. See error - -**Expected behavior** -A clear and concise description of what you expected to happen. - -**Additional context** -Add any other context about the problem here. diff --git a/src/velodyne/.github/ISSUE_TEMPLATE/feature_request.md b/src/velodyne/.github/ISSUE_TEMPLATE/feature_request.md deleted file mode 100644 index d2dbf8d..0000000 --- a/src/velodyne/.github/ISSUE_TEMPLATE/feature_request.md +++ /dev/null @@ -1,20 +0,0 @@ ---- -name: Feature request -about: Suggest an idea for this project -title: '' -labels: enhancement -assignees: JWhitleyAStuff - ---- - -**Is your feature request related to a problem? Please describe.** -A clear and concise description of what the problem is. Ex. I'm always frustrated when [...] - -**Describe the solution you'd like** -A clear and concise description of what you want to happen. - -**Describe alternatives you've considered** -A clear and concise description of any alternative solutions or features you've considered. - -**Additional context** -Add any other context or screenshots about the feature request here. diff --git a/src/velodyne/.github/workflows/basic-build-ci.yaml b/src/velodyne/.github/workflows/basic-build-ci.yaml deleted file mode 100644 index d359893..0000000 --- a/src/velodyne/.github/workflows/basic-build-ci.yaml +++ /dev/null @@ -1,38 +0,0 @@ -name: Basic Build Workflow - -on: - - pull_request - - push - -jobs: - build-noetic: - runs-on: ubuntu-latest - strategy: - fail-fast: false - container: - image: ros:noetic-perception - steps: - - name: Checkout repo - uses: actions/checkout@v2 - - name: Create Workspace - run: | - mkdir src_tmp - mv `find -maxdepth 1 -not -name . -not -name src_tmp` src_tmp/ - mv src_tmp/ src/ - cd src - bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ - catkin_init_workspace' - - name: Install Prerequisites - run: | - bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ - apt-get update && rosdep update; \ - rosdep install --from-paths src --ignore-src -y' - - name: Build Workspace - run: | - bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ - catkin_make' - - name: Run Tests - run: | - bash -c 'source /opt/ros/$ROS_DISTRO/setup.bash; \ - catkin_make run_tests; \ - catkin_test_results --verbose' diff --git a/src/velodyne/.gitignore b/src/velodyne/.gitignore deleted file mode 100644 index da9cbf7..0000000 --- a/src/velodyne/.gitignore +++ /dev/null @@ -1,6 +0,0 @@ -*.pyc -*.tar.gz -*~ -*.user -doc -TAGS diff --git a/src/waypoint_navigation/.gitignore b/src/waypoint_navigation/.gitignore deleted file mode 100644 index dbe9c82..0000000 --- a/src/waypoint_navigation/.gitignore +++ /dev/null @@ -1 +0,0 @@ -.vscode/ \ No newline at end of file diff --git a/src/waypoint_navigation/README.md b/src/waypoint_navigation/README.md index 693cfbc..551bba0 100644 --- a/src/waypoint_navigation/README.md +++ b/src/waypoint_navigation/README.md @@ -2,7 +2,3 @@ - Tkinter 8.6 - Pillow 9.2.0 - ruamel.yaml 0.17.21 - -waypoint_manager 参考 -- https://imagingsolution.net/category/program/python/tkinter/ -- https://daeudaeu.com/tkinter-mousewheel/ diff --git a/src/waypoint_navigation/waypoint_manager/CMakeLists.txt b/src/waypoint_navigation/waypoint_manager/CMakeLists.txt deleted file mode 100644 index 2941813..0000000 --- a/src/waypoint_navigation/waypoint_manager/CMakeLists.txt +++ /dev/null @@ -1,202 +0,0 @@ -cmake_minimum_required(VERSION 3.0.2) -project(waypoint_manager) - -## 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) - -## 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 # Or other packages containing 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 waypoint_manager -# CATKIN_DEPENDS other_catkin_pkg -# 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 -# add_library(${PROJECT_NAME} -# src/${PROJECT_NAME}/waypoint_manager.cpp -# ) - -## Add cmake target dependencies of the library -## as an example, code may need to be generated before libraries -## either from message generation or dynamic reconfigure -# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Declare a C++ executable -## With catkin_make all packages are built within a single CMake context -## The recommended prefix ensures that target names across packages don't collide -# add_executable(${PROJECT_NAME}_node src/waypoint_manager_node.cpp) - -## Rename C++ executable without prefix -## The above recommended prefix causes long target names, the following renames the -## target back to the shorter version for ease of user use -## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" -# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") - -## Add cmake target dependencies of the executable -## same as for the library above -# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) - -## Specify libraries to link a library or executable target against -# target_link_libraries(${PROJECT_NAME}_node -# ${catkin_LIBRARIES} -# ) - -############# -## Install ## -############# - -# 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 -# catkin_install_python(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_waypoint_manager.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/src/waypoint_navigation/waypoint_manager/launch/start_manager.launch b/src/waypoint_navigation/waypoint_manager/launch/start_manager.launch deleted file mode 100644 index e69de29..0000000 --- a/src/waypoint_navigation/waypoint_manager/launch/start_manager.launch +++ /dev/null diff --git a/src/waypoint_navigation/waypoint_manager/package.xml b/src/waypoint_navigation/waypoint_manager/package.xml deleted file mode 100644 index e77ca19..0000000 --- a/src/waypoint_navigation/waypoint_manager/package.xml +++ /dev/null @@ -1,59 +0,0 @@ - - - waypoint_manager - 0.0.0 - The waypoint_manager package - - - - - ubuntu - - - - - - TODO - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - catkin - - - - - - - - diff --git a/src/waypoint_navigation/waypoint_manager/scripts/icons/delete_param_btn.png b/src/waypoint_navigation/waypoint_manager/scripts/icons/delete_param_btn.png new file mode 100644 index 0000000..86f4660 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/icons/delete_param_btn.png Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/icons/new_param_btn.png b/src/waypoint_navigation/waypoint_manager/scripts/icons/new_param_btn.png new file mode 100644 index 0000000..fdf4e36 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/icons/new_param_btn.png Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/__init__.cpython-38.pyc b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/__init__.cpython-38.pyc index 0227a91..02fcd22 100644 --- a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/__init__.cpython-38.pyc +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/__init__.cpython-38.pyc Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/mymaplib.cpython-38.pyc b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/mymaplib.cpython-38.pyc index 5048aa5..cb740e4 100644 --- a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/mymaplib.cpython-38.pyc +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/mymaplib.cpython-38.pyc Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/waypointlib.cpython-38.pyc b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/waypointlib.cpython-38.pyc index f8c3b92..d8faa33 100644 --- a/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/waypointlib.cpython-38.pyc +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/__pycache__/waypointlib.cpython-38.pyc Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/scripts/lib/waypointlib.py b/src/waypoint_navigation/waypoint_manager/scripts/lib/waypointlib.py index ab54d33..94ce65e 100644 --- a/src/waypoint_navigation/waypoint_manager/scripts/lib/waypointlib.py +++ b/src/waypoint_navigation/waypoint_manager/scripts/lib/waypointlib.py @@ -42,6 +42,10 @@ def set_waypoint_val(self, id, key, val): self.waypoints[self.get_num(id)-1][key] = val return + + + def delete_waypoint_param(self, id, key): + return self.waypoints[self.get_num(id)-1].pop(key) def get_waypoint(self, id=None, num=None): @@ -67,8 +71,6 @@ class FinishPose(): def __init__(self, wp_yaml): - super().__init__() - self.header = {} for key, val in wp_yaml["finish_pose"]["header"].items(): self.header[key] = val @@ -95,6 +97,7 @@ + def get_waypoint_yaml(waypoints: WaypointList, finish_pose: FinishPose): s = ["waypoints:" + "\n"] for point in waypoints.get_waypoint(): @@ -108,11 +111,10 @@ seq, stamp, frame = (finish_pose.header["seq"], finish_pose.header["stamp"], finish_pose.header["frame_id"]) s.append(" header: {" + "seq: {}, stamp: {}, frame_id: {}".format(seq,stamp,frame) + "}" + "\n") s.append(" pose:" + "\n") - p = finish_pose.position - s.append(" position: {" + "x: {}, y: {}, z: {}".format(p["x"], p["y"], p["z"]) + "}" + "\n") - o = finish_pose.orientation - s.append(" orientation: {" + "x: {}, y: {}, z: {}, w: {}".format(o["x"],o["y"],o["z"],o["w"]) + "}") + x = finish_pose.x + y = finish_pose.y + z = finish_pose.position["z"] + s.append(" position: {" + "x: {}, y: {}, z: {}".format(x, y, z) + "}" + "\n") + q = quaternion.from_euler_angles([0, 0, finish_pose.yaw]) + s.append(" orientation: {" + "x: {}, y: {}, z: {}, w: {}".format(q.x, q.y, q.z, q.w) + "}") return "".join(s) - - - \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_manager/scripts/manager_GUI.py b/src/waypoint_navigation/waypoint_manager/scripts/manager_GUI.py index 9bd2d1f..24696f8 100755 --- a/src/waypoint_navigation/waypoint_manager/scripts/manager_GUI.py +++ b/src/waypoint_navigation/waypoint_manager/scripts/manager_GUI.py @@ -2,7 +2,11 @@ import tkinter.filedialog import math import ruamel.yaml +import gc +import itertools from pathlib import Path +from tkinter import messagebox +from PIL import Image, ImageTk from lib.mymaplib import MyMap from lib.waypointlib import WaypointList, FinishPose, get_waypoint_yaml @@ -18,7 +22,6 @@ #### 画面上部のメニューを作成 #### self.menu_bar = tk.Menu(self) # メニューバーを配置 self.file_menu = tk.Menu(self.menu_bar, tearoff=tk.OFF) # バーに追加するメニューを作成 - self.menu_bar.add_cascade(label="File", menu=self.file_menu) # Fileメニューとしてバーに追加 self.open_menu = tk.Menu(self.file_menu, tearoff=tk.OFF) # Openメニュー self.open_menu.add_command(label="Map", command=self.menu_open_map) self.open_menu.add_command(label="Waypoints", command=self.menu_open_waypoints, state=tk.DISABLED) @@ -31,23 +34,41 @@ ) self.file_menu.add_separator() self.file_menu.add_command(label="Exit", command=self.menu_exit, accelerator="Ctrl+Q") + self.menu_bar.add_cascade(label="File", menu=self.file_menu) # Fileメニューとしてバーに追加 self.bind_all("", self.menu_save) #キーボードショートカットを設定 self.bind_all("", self.menu_saveas) self.bind_all("", self.menu_exit) - self.master.config(menu=self.menu_bar) # 大元に作成したメニューバーを設定 + + self.edit_menu = tk.Menu(self.menu_bar, tearoff=tk.OFF) + self.edit_menu.add_command(label="Set Finish Pose", command=self.menu_set_finishpose) + self.edit_menu.add_command(label="From To", command=self.menu_from_to) + self.menu_bar.add_cascade(label="Edit", menu=self.edit_menu) + + self.show_menu = tk.Menu(self.menu_bar, tearoff=tk.OFF) + self.fp_menu = tk.Menu(self.show_menu, tearoff=tk.OFF) + self.fp_menu.add_command(label="Set model", command=self.menu_set_footprint) + self.show_fp = tk.BooleanVar() + self.fp_menu.add_checkbutton(label="Show footprint", command=self.menu_show_footprint, + variable=self.show_fp, accelerator="Ctrl+F" + ) + self.show_menu.add_cascade(label="Footprint", menu=self.fp_menu) + self.menu_bar.add_cascade(label="View", menu=self.show_menu) + self.bind_all("", self.menu_show_footprint) + + self.master.configure(menu=self.menu_bar) # 大元に作成したメニューバーを設定 #### 画面上部に、システムからのメッセージを表示するラベルを配置 #### - self.msg_label = tk.Label(self.master, text="Please open map file ", anchor=tk.E) + self.msg_label = tk.Label(self.master, text="Please open map file ", anchor=tk.E, font=("Consolas",13)) self.msg_label.pack(fill=tk.X, padx=5) #### 画面下部に、カーソルの座標やピクセル情報を表示するステータスバーを表示 #### self.status_bar = tk.Frame(self.master) self.mouse_position = tk.Label(self.status_bar, relief=tk.SUNKEN, - text=" (x, y) = ", anchor=tk.W, font=("", 15) + text=" (x, y) = ", anchor=tk.W, font=("Consolas", 15) ) self.mouse_position.pack(side=tk.LEFT, padx=3) self.waypoint_num = tk.Label(self.status_bar, relief=tk.SUNKEN, - text=" Waypoint No. -----", anchor=tk.W, font=("", 15) + text=" Waypoint No. -----", anchor=tk.W, font=("Consolas", 15) ) self.waypoint_num.pack(side=tk.RIGHT, padx=3) self.status_bar.pack(side=tk.BOTTOM, fill=tk.X) @@ -75,16 +96,27 @@ self.master.bind("", self.ctrl_right_click) self.master.bind("", self.window_resize_callback) - #### その他必要になる変数 #### - self.mymap = None - self.waypoints = None - self.finish_pose = None - self.waypoints_filepath = None + #### アイコン #### + icon = Image.open(Path(__file__).parent / Path("icons","new_param_btn.png")) + icon = icon.resize((30, 30)) + self.new_param_icon = ImageTk.PhotoImage(image=icon) + icon = Image.open(Path(__file__).parent / Path("icons","delete_param_btn.png")) + icon = icon.resize((30, 30)) + self.del_param_icon = ImageTk.PhotoImage(image=icon) + + #### その他必要になる変数,オブジェクト #### + self.mymap: MyMap = None + self.waypoints: WaypointList = None + self.finish_pose: FinishPose = None + self.waypoints_filepath: Path = None self.editing_waypoint_id = None # 編集中のウェイポイントを示す図形のオブジェクトID - self.moving_waypoint = False # ウェイポイントをDnDで動かしている最中かどうか + self.moving_waypoint = False # ウェイポイントをmoveで動かしている最中かどうか + self.setting_finish_pose = 0 # finish pose のセット中かどうか self.old_click_point = None # 最後にカーソルのあった座標を保持 - self.wp_info_win = None # ウェイポイント情報を表示するウィンドウ + self.wp_info_win: tk.Toplevel = None # ウェイポイント情報を表示するウィンドウ self.point_rad = 10 # 画像上に示すポイントの半径ピクセル + self.footprint = [[0.25, 0.4], [0.25, -0.4], [-0.65, -0.4], [-0.65, 0.4]] + self.trajectory = [] return @@ -108,7 +140,20 @@ with open(map_path) as file: # .yamlを読み込む map_yaml = ruamel.yaml.YAML().load(file) - self.mymap = MyMap(Path(map_path), map_yaml) + if not "image" in map_yaml.keys(): + messagebox.showerror(title="Format error", message="Selected map file is unexpected format.") + return + try: + del self.mymap + self.mymap = MyMap(Path(map_path), map_yaml) + except FileNotFoundError: + messagebox.showerror(title="Image file is not found", message="\""+map_yaml["image"]+"\" is not found.") + self.mymap = None + return + self.message("Read map file " + map_path) + self.canvas.delete("all") + self.trajectory = [] + if self.waypoints is not None: self.waypoints.number_dict = {} ## キャンバスサイズに合わせて画像を表示 scale = 1 offset_x = 0 @@ -126,10 +171,18 @@ self.mymap.translate(offset_x, offset_y) self.draw_image() # 画像を描画 self.plot_origin() # 原点を示す円を描画 - self.master.title(Path(map_path).name + " - " + self.master.title()) - self.open_menu.entryconfigure("Map", state=tk.DISABLED) + if self.waypoints_filepath is not None: + self.master.title(self.waypoints_filepath.name + " - " + Path(map_path).name) + else: + self.master.title(Path(map_path).name) self.open_menu.entryconfigure("Waypoints", state=tk.NORMAL) - self.message("Please open waypoints file ") + if self.waypoints is None: + self.message("Please open waypoints file ") + self.menu_open_waypoints() + else: + self.plot_waypoints() + self.draw_trajectory() + gc.collect() return @@ -137,23 +190,45 @@ +++++ File -> Open -> Waypionts +++++ """ def menu_open_waypoints(self): + if (self.waypoints is not None) and (self.master.title()[0] == "*"): + yn = messagebox.askyesno("Confirm", "Do you want to save changes to " + str(self.waypoints_filepath)) + if yn: self.save_waypoints(str(self.waypoints_filepath)) # Yes + self.master.title(str(self.master.title()).replace("* " + self.waypoints_filepath.name + " - ", "")) + elif (self.waypoints is not None): + self.master.title(str(self.master.title()).replace(self.waypoints_filepath.name + " - ", "")) + filepath = tkinter.filedialog.askopenfilename( parent=self.master, - title="Select map yaml file", + title="Select waypoints yaml file", initialdir=str(Path(".")), filetypes=[("YAML", ".yaml")] ) if not filepath: return with open(filepath) as file: wp_yaml = ruamel.yaml.YAML().load(file) + if (not "waypoints" in wp_yaml.keys()) or (not "finish_pose" in wp_yaml.keys()): + messagebox.showerror(title="Format error", message="Selected waypoints file is unexpected format.") + return + + self.canvas.delete("all") + self.trajectory = [] + self.draw_image() + self.plot_origin() + if (self.wp_info_win is not None) and (self.wp_info_win.winfo_exists()): + self.wp_info_win.destroy() + + del self.waypoints self.waypoints = WaypointList(wp_yaml) self.finish_pose = FinishPose(wp_yaml) self.waypoints_filepath = Path(filepath) self.plot_waypoints() - self.master.title(Path(filepath).name + " - " + self.master.title()) + self.draw_trajectory() + self.master.title(self.waypoints_filepath.name + " - " + self.master.title()) + self.message("Read waypoints file " + filepath) self.file_menu.entryconfigure("Save", state=tk.NORMAL) self.file_menu.entryconfigure("Save As", state=tk.NORMAL) self.popup_menu.entryconfigure("Add waypoint here", state=tk.NORMAL) + gc.collect() return @@ -161,8 +236,11 @@ +++++ File -> Save +++++ """ def menu_save(self, event=None): + if not self.waypoints: return self.save_waypoints(str(self.waypoints_filepath)) self.message("Saved changes!") + title = self.master.title() + if title[0] == "*": self.master.title(str(title).replace("* ", "")) return @@ -170,6 +248,7 @@ +++++ File -> Save As +++++ """ def menu_saveas(self, event=None): + if not self.waypoints: return new_filepath = tkinter.filedialog.asksaveasfilename( parent=self.master, title="Save As", @@ -184,6 +263,8 @@ self.waypoints_filepath = Path(new_filepath) self.master.title(current_title.replace(old_filename, self.waypoints_filepath.name)) self.message("Save As" + "\"" + str(new_filepath) + "\"") + title = self.master.title() + if title[0] == "*": self.master.title(str(title).replace("* ", "")) return @@ -191,6 +272,13 @@ +++++ File -> Exit +++++ """ def menu_exit(self, event=None): + title = self.master.title() + if title[0] != "*": + self.master.destroy() + return + res = messagebox.askyesnocancel(title="Unsaved changes", message="Do you want to save changes before close?") + if res is None: return # cancel + if res == True: self.menu_save() self.master.destroy() @@ -201,6 +289,150 @@ with open(path, 'w') as f: f.write(get_waypoint_yaml(self.waypoints, self.finish_pose)) return + + + """ + +++++ Edit -> Set Finish Pose +++++ + """ + def menu_set_finishpose(self, event=None): + if not self.waypoints: return + self.message("Click any point to set finsih pose. If you want to cancel, right click anywhere.") + self.setting_finish_pose = 1 + return + + + """ + +++++ Edit -> From To +++++ + """ + def menu_from_to(self, event=None): + if not self.waypoints: return + sub_win = tk.Toplevel() + sub_win.title("Set parameter from some number's waypoint to any number's one") + sub_win.attributes('-topmost', True) # サブウィンドウを最前面で固定 + # + font = ("Consolas", 12) + frame1 = tk.Frame(sub_win) + from_label = tk.Label(frame1, text="From No.", font=font) + from_label.grid(row=0, column=0) + from_txt_box = tk.Entry(frame1, width=4, font=font) + from_txt_box.grid(row=0, column=1) + to_label = tk.Label(frame1, text="to No.", font=font) + to_label.grid(row=0, column=2) + to_txt_box = tk.Entry(frame1, width=4, font=font) + to_txt_box.grid(row=0, column=3) + frame1.pack(padx=10, pady=10) + # + frame2 = tk.Frame(sub_win) + name_label = tk.Label(frame2, text="Parameter", font=font) + name_label.grid(row=0, column=0) + value_label=tk.Label(frame2, text="Value", font=font) + value_label.grid(row=0, column=1) + name_txt_box = tk.Entry(frame2, width=20, font=font) + name_txt_box.grid(row=1, column=0, padx=20) + value_txt_box = tk.Entry(frame2, width=20, font=font) + value_txt_box.grid(row=1, column=1, padx=20) + frame2.pack(padx=10, pady=10) + # + def set_btn_callback(): + from_num = from_txt_box.get() + to_num = to_txt_box.get() + if (len(from_num) == 0) or (len(to_num) == 0): + messagebox.showwarning(title="Warning", message="Enter waypoint numbers.") + return + from_num = int(from_num) + to_num = int(to_num) + if (from_num < 1) or (to_num > len(self.waypoints.get_waypoint())): + messagebox.showerror(title="Error", message="Entered number is out of range of the number of waypoints") + return + param = name_txt_box.get() + value = value_txt_box.get() + if (len(param) == 0) or (len(value) == 0): + messagebox.showwarning(title="Warning", message="Enter parameter name and value") + return + for n in range(from_num, to_num+1): + self.waypoints.waypoints[n-1][param] = value + sub_win.destroy() + self.update_title() + self.plot_waypoints() + self.draw_trajectory() + return + frame3 = tk.Frame(sub_win) + set_btn = tk.Button(frame3, text="Set", width=5, command=set_btn_callback) + set_btn.pack(side=tk.RIGHT, padx=50, pady=10) + cancel_btn = tk.Button(frame3, text="Cancel", width=8, command=sub_win.destroy) + cancel_btn.pack(side=tk.LEFT, padx=50, pady=10) + frame3.pack(padx=10, pady=20, expand=True, fill=tk.X) + return + + + """ + +++++ View -> Footprint -> Set +++++ + """ + def menu_set_footprint(self, event=None): + sub_win = tk.Toplevel() + sub_win.title("Set footprint model") + sub_win.protocol("WM_DELETE_WINDOW") + sub_win.attributes('-topmost', True) # サブウィンドウを最前面で固定 + # テキストボックス + footprint = str(self.footprint) + txt_box = tk.Entry(sub_win, width=len(footprint)+10, font=("Consolas",12)) + txt_box.insert(tk.END, footprint) + txt_box.pack(padx=10, pady=20) + # Set ボタンコールバック + def callback(): + try: + self.footprint = eval(txt_box.get()) + if self.show_fp.get(): + self.show_fp.set(False) + self.menu_show_footprint() + self.show_fp.set(True) + self.menu_show_footprint() + sub_win.destroy() + except SyntaxError: + sub_win.title("Unexpectd format") + return + # Set ボタン + set_btn = tk.Button(sub_win, text="Set", width=5, height=1, command=callback) + set_btn.pack(pady=10) + sub_win.update() + w = sub_win.winfo_width() + h = sub_win.winfo_height() + x = int((self.canv_w - w) / 2) + y = int((self.canv_h - h) / 2) + geometry = "{}x{}+{}+{}".format(w, h, x, y) + sub_win.geometry(geometry) + return + + + """ + +++++ View -> Footprint -> Show +++++ + """ + def menu_show_footprint(self, event=None): + if not self.waypoints: return + if event: self.show_fp.set(not self.show_fp.get()) + # create polygon as footprint + def create_footprint(x, y, nx, ny): + polygon = [] + th = math.atan2((ny - y), (nx -x)) + for xy in self.footprint: + X = xy[0]*math.cos(th) - xy[1]*math.sin(th) + x + Y = xy[0]*math.sin(th) + xy[1]*math.cos(th) + y + cx, cy = self.real2canvas(float(X), float(Y)) + polygon.append([cx, cy]) + id = self.canvas.create_polygon(polygon, fill="", outline="green", tags="footprint") + self.canvas.lift("footprint", "map_image") + return + ## + if (self.show_fp.get()): + for i in range(len(self.waypoints.get_waypoint()) - 1): + wp = self.waypoints.get_waypoint(num=i+1) + next_wp = self.waypoints.get_waypoint(num=i+2) + create_footprint(float(wp["x"]), float(wp["y"]), float(next_wp["x"]), float(next_wp["y"])) + # last waypoint + create_footprint(float(next_wp["x"]), float(next_wp["y"]), self.finish_pose.x, self.finish_pose.y) + else: + self.canvas.delete("footprint") + return @@ -213,16 +445,18 @@ +++++ 地図上の原点に円を描画 +++++ """ def plot_origin(self): - x, y = self.mymap.transform(self.mymap.img_origin[0], self.mymap.img_origin[1]) + cx, cy = self.mymap.transform(self.mymap.img_origin[0], self.mymap.img_origin[1]) r = self.point_rad # 円の半径(ピクセル) - x0 = x - r - y0 = y - r - x1 = x + r + 1 - y1 = y + r + 1 + x0 = cx - r + y0 = cy - r + x1 = cx + r + 1 + y1 = cy + r + 1 if self.canvas.find_withtag("origin"): self.canvas.moveto("origin", x0, y0) + self.trajectory[0] = [cx, cy] else: self.canvas.create_oval(x0, y0, x1, y1, tags="origin", fill='cyan', outline='blue') + self.trajectory.append([cx, cy]) return @@ -237,7 +471,8 @@ cx, cy = self.real2canvas(float(wp["x"]), float(wp["y"])) x0 = cx - self.point_rad y0 = cy - self.point_rad - self.canvas.moveto(id, round(x0), round(y0)) + self.canvas.moveto(id, x0, y0) + self.trajectory[self.waypoints.get_num(id)] = [cx, cy] return if len(self.waypoints.get_id_list()) == 0: @@ -252,7 +487,8 @@ cx, cy = self.real2canvas(float(wp["x"]), float(wp["y"])) x0 = cx - self.point_rad y0 = cy - self.point_rad - self.canvas.moveto(id, round(x0), round(y0)) + self.canvas.moveto(id, x0, y0) + self.trajectory[self.waypoints.get_num(id)] = [cx, cy] # trajectory # Finish poseを描画 cx, cy = self.real2canvas(self.finish_pose.x, self.finish_pose.y) x0 = cx @@ -263,25 +499,50 @@ # movetoだと上手くいかないので、毎回削除、再描画 self.canvas.delete(self.finish_pose.id) self.finish_pose.id = self.canvas.create_line(x0, y0, x1, y1, tags="finish_pose", - width=10, arrow=tk.LAST, arrowshape=(12,15,9), fill="#AAF" + width=10, arrow=tk.LAST, arrowshape=(12,15,9), fill="#AAF" ) + # trajectory + if self.canvas.find_withtag("trajectory"): + self.trajectory[-1] = [cx, cy] + else: + self.trajectory.append([cx, cy]) return """ + +++++ ウェイポイントをつないだ軌道を描画する +++++ + """ + def draw_trajectory(self): + if self.canvas.find_withtag("trajectory"): + self.canvas.coords("trajectory", list(itertools.chain.from_iterable(self.trajectory))) + else: + self.canvas.create_line(list(itertools.chain.from_iterable(self.trajectory)), + fill="#DF2", width=2, tags="trajectory") + self.canvas.lift("trajectory", "map_image") + return + + + """ +++++ キャンバスに新たなウェイポイントを描画する +++++ """ def create_waypoint(self, waypoint: dict): + img_x, img_y = self.mymap.real2image(float(waypoint["x"]), float(waypoint["y"])) cx, cy = self.real2canvas(float(waypoint["x"]), float(waypoint["y"])) - x0 = round(cx - self.point_rad) - y0 = round(cy - self.point_rad) - x1 = round(cx + self.point_rad + 1) - y1 = round(cy + self.point_rad + 1) - id = self.canvas.create_oval(x0, y0, x1, y1, fill='#FDD', outline='red', activefill='red') - self.canvas.tag_bind(id, "", lambda event, wp_id=id: self.waypoint_clicked(event, wp_id)) - self.canvas.tag_bind(id, "", lambda event, wp_id=id: self.waypoint_enter(event, wp_id)) - self.canvas.tag_bind(id, "", self.waypoint_leave) - self.canvas.tag_bind(id, "", self.waypoint_click_move) + x0 = (cx - self.point_rad) + y0 = (cy - self.point_rad) + x1 = (cx + self.point_rad + 1) + y1 = (cy + self.point_rad + 1) + if (img_x < 0) or (img_y < 0) or (img_x > self.mymap.width()) or (img_y > self.mymap.height()): + id = self.canvas.create_oval(x0, y0, x1, y1, fill='#FEE', outline='#FAA', activefill='#F88', tags="waypoints") + self.canvas.tag_bind(id, "", lambda event, wp_id=id: self.waypoint_enter(event, wp_id)) + self.canvas.tag_bind(id, "", self.waypoint_leave) + else: + id = self.canvas.create_oval(x0, y0, x1, y1, fill='#FDD', outline='red', activefill='red', tags="waypoints") + self.canvas.tag_bind(id, "", lambda event, wp_id=id: self.waypoint_clicked(event, wp_id)) + self.canvas.tag_bind(id, "", lambda event, wp_id=id: self.waypoint_enter(event, wp_id)) + self.canvas.tag_bind(id, "", self.waypoint_leave) + self.canvas.tag_bind(id, "", self.waypoint_click_move) + self.trajectory.append([cx, cy]) #trajectory return id @@ -292,9 +553,10 @@ if wp_id != self.editing_waypoint_id: # 編集中のウェイポイントを切り替え self.canvas.itemconfig(self.editing_waypoint_id, fill='#FDD') self.editing_waypoint_id = wp_id - self.canvas.itemconfig(wp_id, fill='red') - self.disp_waypoint_info(wp_id) - self.message("Show selected waypoint information") + self.canvas.itemconfig(wp_id, fill='red') + self.moving_waypoint = False + self.disp_waypoint_info(wp_id) + self.message("Show selected waypoint information") return @@ -310,22 +572,26 @@ delta_y = event.y-self.old_click_point[1] self.canvas.move(self.editing_waypoint_id, delta_x, delta_y) box = self.canvas.bbox(self.editing_waypoint_id) - px = (box[2] + box[0]) / 2 # ウィンドウ上の座標 - py = (box[3] + box[1]) / 2 - img_x, img_y = self.mymap.inv_transform(px, py) + cx = (box[2] + box[0]) / 2 # ウィンドウ上の座標 + cy = (box[3] + box[1]) / 2 + img_x, img_y = self.mymap.inv_transform(cx, cy) # マップ画像上の座標を、実際の座標に変換 x, y = self.mymap.image2real(img_x, img_y) # 編集中のウェイポイント情報を更新 self.waypoints.set_waypoint_val(self.editing_waypoint_id, "x", x) self.waypoints.set_waypoint_val(self.editing_waypoint_id, "y", y) # 表示中のウェイポイント情報を更新 - txt_box = self.wp_info_win.grid_slaves(column=1, row=0)[0] + txt_box: tk.Entry = self.wp_info_win.grid_slaves(column=1, row=0)[0] txt_box.delete(0, tk.END) txt_box.insert(tk.END, x) txt_box = self.wp_info_win.grid_slaves(column=1, row=1)[0] txt_box.delete(0, tk.END) txt_box.insert(tk.END, y) self.old_click_point = [event.x, event.y] + self.update_title() + # trajectory + self.trajectory[self.waypoints.get_num(self.editing_waypoint_id)] = [cx, cy] + self.draw_trajectory() return @@ -334,10 +600,10 @@ """ def waypoint_enter(self, event, wp_id): wp_num = self.waypoints.get_num(wp_id) - self.waypoint_num["text"] = " Waypoint No. {} " .format(str(wp_num)) + self.waypoint_num["text"] = " Waypoint No. {} " .format(str(wp_num)) def waypoint_leave(self, event): - self.waypoint_num["text"] = " Waypoint No. ----- " + self.waypoint_num["text"] = " Waypoint No. ----- " @@ -350,47 +616,52 @@ +++++ ウェイポイントが左クリックされたとき、別窓で情報を表示する関数 +++++ """ def disp_waypoint_info(self, id): - point = self.waypoints.get_waypoint(id=id) - if (self.wp_info_win is None) or (not self.wp_info_win.winfo_exists()): - # ウィンドウが表示されてない場合、初期化 - self.wp_info_win = tk.Toplevel() - self.wp_info_win.lower() - self.wp_info_win.protocol("WM_DELETE_WINDOW", self.close_wp_info) - # ウェイポイントファイルのキーを取得し、ラベルとテキストボックスを配置 - for i, key in enumerate(point.keys()): - key_label = tk.Label(self.wp_info_win, text=key+":", width=6, font=("Consolas",15), anchor=tk.E) - key_label.grid(column=0, row=i, padx=2, pady=5) - txt_box = tk.Entry(self.wp_info_win, width=20, font=("Consolas", 15)) - txt_box.insert(tk.END, str(point[key]).lower()) - txt_box.grid(column=1, row=i, padx=2, pady=2, ipady=3, sticky=tk.EW) - # Apply, DnD(Drag & Drop), remove ボタン - canv = tk.Canvas(self.wp_info_win) - canv.grid(column=0, columnspan=2, row=self.wp_info_win.grid_size()[1], sticky=tk.EW) - apply_btn = tk.Button(canv, text="Apply", width=5, height=1, bg="#FDD", - command=self.apply_btn_callback) - apply_btn.pack(side=tk.RIGHT, anchor=tk.SE, padx=5, pady=5) - dnd_btn = tk.Button(canv, text="DnD", width=5, height=1, bg="#EEE") - dnd_btn["command"] = lambda obj=dnd_btn: self.dnd_btn_callback(dnd_btn) - dnd_btn.pack(side=tk.RIGHT, anchor=tk.SE, padx=5, pady=5) - remove_btn = tk.Button(canv, text="Remove", width=7, height=1, bg="#F00", - command=self.remove_btn_callback) - remove_btn.pack(side=tk.LEFT, anchor=tk.SE, padx=5, pady=5) - # 位置とサイズを設定 - self.wp_info_win.update() - w = self.wp_info_win.winfo_width() - h = self.wp_info_win.winfo_height() - x = self.master.winfo_x() + self.canv_w - w - y = self.master.winfo_y() + self.canv_h - h - geometry = "{}x{}+{}+{}".format(w, h, x, y) - self.wp_info_win.geometry(geometry) - self.wp_info_win.lift() - self.wp_info_win.attributes('-topmost', True) # サブウィンドウを最前面で固定 - else: - # 既にウィンドウが表示されている場合、テキストボックスの中身を変える - for i, key in enumerate(point): - txt_box = self.wp_info_win.grid_slaves(column=1, row=i)[0] - txt_box.delete(0, tk.END) - txt_box.insert(tk.END, str(point[key]).lower()) + point: dict = self.waypoints.get_waypoint(id=id) + if (self.wp_info_win is not None) and (self.wp_info_win.winfo_exists()): + # 既にウィンドウが表示されている場合、一度削除 + self.wp_info_win.destroy() + # ウィンドウが表示されてない場合、初期化 + self.wp_info_win = tk.Toplevel() + self.wp_info_win.lower() + self.wp_info_win.protocol("WM_DELETE_WINDOW", self.close_wp_info) + # ウェイポイントファイルのキーを取得し、ラベルとテキストボックスを配置 + label_width = max([len(key) for key in point.keys()]) + 2 + for i, key in enumerate(point.keys()): + key_label = tk.Label(self.wp_info_win, text=key+":", width=label_width, font=("Consolas",15), anchor=tk.E) + key_label.grid(column=0, row=i, padx=2, pady=5) + txt_box = tk.Entry(self.wp_info_win, width=20, font=("Consolas", 15)) + txt_box.insert(tk.END, str(point[key]).lower()) + txt_box.grid(column=1, row=i, padx=2, pady=2, ipady=3, sticky=tk.EW) + del_btn = tk.Button(self.wp_info_win, image=self.del_param_icon, relief=tk.FLAT) + del_btn["command"] = lambda name=key, val=str(point[key]).lower(): self.del_param_btn_callback(name, val) + del_btn.grid(column=2, row=i, padx=5, pady=5) + self.wp_info_win.grid_columnconfigure(1, weight=1) + # New parameter + new_param_btn = tk.Button(self.wp_info_win, image=self.new_param_icon, relief=tk.FLAT) + new_param_btn["command"] = self.new_param_btn_callback + new_param_btn.grid(column=0, columnspan=3, row=self.wp_info_win.grid_size()[1], pady=10) + # Apply, Move(Drag & Drop), remove ボタン + canv = tk.Canvas(self.wp_info_win) + canv.grid(column=0, columnspan=3, row=self.wp_info_win.grid_size()[1], sticky=tk.EW, pady=5) + apply_btn = tk.Button(canv, text="Apply", width=5, height=1, bg="#FDD", + command=self.apply_btn_callback) + apply_btn.pack(side=tk.RIGHT, anchor=tk.SE, padx=5, pady=5) + self.wp_info_win.bind('', self.apply_btn_callback) + move_btn = tk.Button(canv, text="Move", width=5, height=1, bg="#EEE") + move_btn["command"] = lambda obj=move_btn: self.move_btn_callback(move_btn) + move_btn.pack(side=tk.RIGHT, anchor=tk.SE, padx=5, pady=5) + remove_btn = tk.Button(canv, text="Remove", width=7, height=1, bg="#F00", + command=self.remove_btn_callback) + remove_btn.pack(side=tk.LEFT, anchor=tk.SE, padx=5, pady=5) + # 位置とサイズを設定 + self.wp_info_win.update() + w = self.wp_info_win.winfo_width() + h = self.wp_info_win.winfo_height() + x = self.canvas.winfo_x() + self.canv_w - w -10 + y = self.canvas.winfo_y() + self.canv_h - h -10 + self.wp_info_win.lift() + self.wp_info_win.attributes('-topmost', True) # サブウィンドウを最前面で固定 + self.wp_info_win.geometry("+{}+{}".format(x, y)) self.wp_info_win.title("Waypoint " + str(self.waypoints.get_num(id))) # タイトルを設定 return @@ -398,20 +669,26 @@ """ +++++ Applyボタンを押したときのコールバック +++++ """ - def apply_btn_callback(self): + def apply_btn_callback(self, event=None): + if (event is not None) and (event.keysym != "Return"): return point = self.waypoints.get_waypoint(id=self.editing_waypoint_id) for i, key in enumerate(point.keys()): txt_box = self.wp_info_win.grid_slaves(column=1, row=i)[0] - self.waypoints.set_waypoint_val(self.editing_waypoint_id, key, txt_box.get()) - self.plot_waypoints(id=self.editing_waypoint_id) - self.message("Apply changes of waypoint parameters") + val = txt_box.get() + if (str(point[key]) == val): continue + self.update_title() + self.message("Apply changes of waypoint parameters") + self.waypoints.set_waypoint_val(self.editing_waypoint_id, key, val) + if ((key == "x") or (key == "y")): + self.plot_waypoints(self.editing_waypoint_id) + self.draw_trajectory() return """ - +++++ ドラッグ&ドロップボタン(DnD)を押したときのコールバック +++++ + +++++ ドラッグ&ドロップボタン(Moveボタン)を押したときのコールバック +++++ """ - def dnd_btn_callback(self, obj=None): + def move_btn_callback(self, obj=None): if obj is None: return btn = obj # 押された状態とそうでない状態を切り替える @@ -432,20 +709,85 @@ +++++ removeボタンを押したときのコールバック +++++ """ def remove_btn_callback(self): - self.waypoints.remove(self.editing_waypoint_id) - self.canvas.delete(self.editing_waypoint_id) # ウェイポイントを示す円を削除 - self.close_wp_info() - self.message("Removed waypoint") + yn = messagebox.askyesno("Delete parameter", message="Are you sure you want to remove this waypoint?") + if (yn == True): + self.trajectory.pop(self.waypoints.get_num(self.editing_waypoint_id)) + self.waypoints.remove(self.editing_waypoint_id) + self.canvas.delete(self.editing_waypoint_id) # ウェイポイントを示す円を削除 + self.close_wp_info() + self.message("Removed waypoint") + self.update_title() + self.draw_trajectory() return """ + +++++ New Parameter ボタンを押したときのコールバック +++++ + """ + def new_param_btn_callback(self): + # Sub window + sub_win = tk.Toplevel() + sub_win.title("Add new parameter") + sub_win.attributes('-topmost', True) + font = ("Consolas",15) + # Message label + label = tk.Label(sub_win, text="Name : Value", font=font, anchor=tk.CENTER, width=20) + label.grid(row=0, column=0, columnspan=3, padx=10, pady=10) + # Text box + name_entry = tk.Entry(sub_win, font=font, width=15) + name_entry.grid(column=0, row=1, padx=10, pady=5) + colon = tk.Label(sub_win, text=":", font=font, anchor=tk.CENTER, width=2) + colon.grid(row=1, column=1) + value_entry = tk.Entry(sub_win, font=font, width=15) + value_entry.grid(column=2, row=1, padx=10, pady=5) + # Buttons + def add_param(): + name = name_entry.get() + value = value_entry.get() + self.waypoints.set_waypoint_val(self.editing_waypoint_id, key=name, val=value) + sub_win.destroy() + self.wp_info_win.destroy() + self.disp_waypoint_info(self.editing_waypoint_id) + self.update_title() + gc.collect() + return + add_btn = tk.Button(sub_win, text="Add", width=5, height=1, font=font, anchor=tk.CENTER, bg="#AFA") + add_btn["command"] = add_param + add_btn.grid(column=2, row=2, pady=20) + cancel_btn = tk.Button(sub_win, text="Cancel", width=7, height=1, font=font, anchor=tk.CENTER) + cancel_btn["command"] = sub_win.destroy + cancel_btn.grid(column=0, row=2, pady=20) + # Window position + sub_win.update() + w = sub_win.winfo_width() + 10 + h = sub_win.winfo_height() + x = int((self.canv_w - w) / 2) + y = int((self.canv_h - h) / 2) + sub_win.geometry("{}x{}+{}+{}".format(w, h, x, y)) + return + + + def del_param_btn_callback(self, name, val): + msg = "Are you sure you want to delete this parameter?\n\n" + msg += str(name) + ": " + str(val) + yn = messagebox.askyesno("Delete parameter", message=msg) + if (yn == True): + self.waypoints.delete_waypoint_param(self.editing_waypoint_id, name) + self.wp_info_win.destroy() + self.disp_waypoint_info(self.editing_waypoint_id) + self.update_title() + return + + + """ +++++ ウェイポイント情報を表示するサブウィンドウを閉じたときのコールバック +++++ """ def close_wp_info(self): self.canvas.itemconfig(self.editing_waypoint_id, fill='#FDD') self.editing_waypoint_id = None + self.moving_waypoint = False self.wp_info_win.destroy() + gc.collect() return @@ -461,16 +803,16 @@ def add_waypoint_here(self): if (self.wp_info_win is not None) and (self.wp_info_win.winfo_exists()): self.close_wp_info() - img_xy = self.right_click_coord - if self.mymap.pil_img.getpixel((img_xy[0], img_xy[1]))[0] == 0: - self.message("There is obstacles") + img_x, img_y = self.right_click_coord + if self.mymap.pil_img.getpixel((img_x, img_y))[0] == 0: + messagebox.showwarning(title="Warning", message="There is obstacles") return # 何番目のウェイポイントの次に追加するか入力させる add_wp_win = tk.Toplevel() add_wp_win.title("Add waypoint") add_wp_win.protocol("WM_DELETE_WINDOW") add_wp_win.attributes('-topmost', True) # サブウィンドウを最前面で固定 - msg = tk.Label(add_wp_win, text="Add waypoint after no. ", font=("Consolas",15), anchor=tk.E) + msg = tk.Label(add_wp_win, text="Add new waypoint at no. ", font=("Consolas",15), anchor=tk.E) msg.grid(column=0, row=0, padx=10, pady=10, sticky=tk.EW) txt_box = tk.Entry(add_wp_win, width=4, font=("Consolas",15)) txt_box.grid(column=1, row=0, pady=10, sticky=tk.W) @@ -494,12 +836,19 @@ +++++ add waypoint hereをクリックして開いた別窓のAddボタンのコールバック +++++ """ def add_btn_callback(self, num_box: tk.Entry, win: tk.Toplevel): - prev_num = num_box.get() - if (prev_num == ""): - self.message("Please enter number") + num = num_box.get() + if (num == ""): + win.attributes('-topmost', False) + messagebox.showwarning(title="Warning", message="The number has not been entered.") + win.attributes('-topmost', True) + return + num = int(num) + if (num < 1) or (num > len(self.waypoints.waypoints)+1): + win.attributes('-topmost', False) + messagebox.showwarning(title="Warning", message="The number is out of range.") + win.attributes('-topmost', True) return win.destroy() - prev_num = int(prev_num) img_xy = self.right_click_coord # ウェイポイント座標を計算 x, y = self.mymap.image2real(img_xy[0], img_xy[1]) @@ -511,11 +860,15 @@ elif (key=="z"): point[key] = 0.0 else: point[key] = "" id = self.create_waypoint(point) - self.waypoints.insert(prev_num+1, point, id=id) + cx,cy = self.trajectory.pop(-1) + self.trajectory[num:num] = [[cx, cy]] + self.waypoints.insert(num, point, id=id) self.plot_waypoints(id=id) + self.draw_trajectory() self.editing_waypoint_id = id self.canvas.itemconfig(id, fill='red') self.disp_waypoint_info(id) + self.update_title() return @@ -530,29 +883,24 @@ """ def mouse_move(self, event): if not self.mymap: return + + if self.setting_finish_pose == 2: + x0, y0, _, _ = self.canvas.coords("set_finish_pose") + x, y = event.x, event.y + theta = math.atan2((-y+y0), (x-x0)) + x1 = x0 + math.cos(theta) * self.point_rad * 3 + y1 = y0 - math.sin(theta) * self.point_rad * 3 + self.canvas.delete("set_finish_pose") + self.canvas.create_line(x0, y0, x1, y1, tags="set_finish_pose", + width=10, arrow=tk.LAST, arrowshape=(12,15,9), fill="#F88" + ) + img_x, img_y = self.mymap.inv_transform(event.x, event.y) if (img_x < 0) or (img_y < 0) or (img_x > self.mymap.width()) or (img_y > self.mymap.height()): self.mouse_position["text"] = " Out of map " return x, y = self.mymap.image2real(img_x, img_y) - self.mouse_position["text"] = " ( x, y ) = ( {}, {} ) ".format(x, y) - return - - - """ - +++++ マウスホイールを回転したとき(タッチパッドをドラッグしたとき) +++++ - """ - def mouse_wheel(self, event): - if not self.mymap: return - if event.delta > 0: - # 上に回転(タッチパッドなら下にドラッグ)=> 拡大 - self.mymap.scale_at(event.x, event.y, 1.1) - else: - # 下に回転(タッチパッドなら上にドラッグ)=> 縮小 - self.mymap.scale_at(event.x, event.y, 0.9) - self.draw_image() - self.plot_origin() - self.plot_waypoints() + self.mouse_position["text"] = " ( x, y ) = ( {}, {} ) ".format(x, y) return @@ -561,6 +909,43 @@ """ def left_click(self, event): self.popup_menu.unpost() # 右クリックで出るポップアップメニューを非表示 + + if self.setting_finish_pose == 1: + x0, y0 = event.x, event.y + img_x, img_y = self.mymap.inv_transform(x0, y0) + if (img_x < 0) or (img_y < 0) or (img_x > self.mymap.width()) or (img_y > self.mymap.height()): + retry = messagebox.askretrycancel(title="Cannot set finish pose here", message="The point is out of the map.") + if not retry: self.setting_finish_pose = 0 + return + x1 = x0 + math.cos(self.finish_pose.yaw) * self.point_rad * 3 + y1 = y0 - math.sin(self.finish_pose.yaw) * self.point_rad * 3 + self.canvas.create_line(x0, y0, x1, y1, tags="set_finish_pose", + width=10, arrow=tk.LAST, arrowshape=(12,15,9), fill="#F88" + ) + self.setting_finish_pose = 2 + return + + if self.setting_finish_pose == 2: + x0, y0, _, _ = self.canvas.coords("set_finish_pose") + x, y = event.x, event.y + theta = math.atan2((-y+y0), (x-x0)) + x1 = x0 + math.cos(theta) * self.point_rad * 3 + y1 = y0 - math.sin(theta) * self.point_rad * 3 + self.canvas.delete("set_finish_pose") + self.canvas.delete(self.finish_pose.id) + self.finish_pose.id = self.canvas.create_line(x0, y0, x1, y1, tags="finish_pose", + width=10, arrow=tk.LAST, arrowshape=(12,15,9), fill="#AAF" + ) + self.trajectory[-1] = [x0, y0] + self.draw_trajectory() + img_x, img_y = self.mymap.inv_transform(x0, y0) + real_x, real_y = self.mymap.image2real(img_x, img_y) + self.finish_pose.x = real_x + self.finish_pose.y = real_y + self.finish_pose.yaw = theta + self.setting_finish_pose = 0 + self.message("New finish pose is set.") + self.update_title() return @@ -570,6 +955,7 @@ def left_click_move(self, event): if not self.mymap: return if self.moving_waypoint: return + if self.setting_finish_pose != 0: return if self.old_click_point is None: self.old_click_point = [event.x, event.y] return @@ -582,9 +968,14 @@ # origin, waypoints finish_pose を平行移動 self.canvas.move("origin", delta_x, delta_y) if self.waypoints: - for id in self.waypoints.get_id_list(): - self.canvas.move(id, delta_x, delta_y) + self.canvas.move("waypoints", delta_x, delta_y) self.canvas.move("finish_pose", delta_x, delta_y) + self.canvas.move("trajectory", delta_x, delta_y) + self.canvas.lift("trajectory", "map_image") + self.canvas.move("footprint", delta_x, delta_y) + for i in range(0, len(self.trajectory)): + self.trajectory[i][0] = self.trajectory[i][0] + delta_x + self.trajectory[i][1] = self.trajectory[i][1] + delta_y self.old_click_point = [event.x, event.y] return @@ -602,6 +993,15 @@ """ def right_click(self, event): if not self.mymap: return + if self.setting_finish_pose == 1: + self.setting_finish_pose = 0 + self.message("Canceled.") + return + if self.setting_finish_pose == 2: + self.canvas.delete("set_finish_pose") + self.setting_finish_pose = 0 + self.message("Canceled.") + return # クリックした座標の近くにあるオブジェクトを取得 clicked_obj = self.canvas.find_enclosed(event.x-20, event.y-20, event.x+20, event.y+20) if clicked_obj: # 何かオブジェクトがクリックされていた場合 @@ -621,10 +1021,14 @@ """ def ctrl_left_click(self, event): if not self.mymap: return - self.mymap.scale_at(event.x, event.y, 1.2) + if self.setting_finish_pose != 0: return + scale = 1.2 + self.mymap.scale_at(event.x, event.y, scale) self.draw_image() self.plot_origin() self.plot_waypoints() + self.canvas.scale("footprint", event.x, event.y, scale, scale) + self.canvas.scale("trajectory", event.x, event.y, scale, scale) self.message("Zoom In") return @@ -634,15 +1038,37 @@ """ def ctrl_right_click(self, event): if not self.mymap: return - self.mymap.scale_at(event.x, event.y, 0.8) + if self.setting_finish_pose != 0: return + scale = 0.8 + self.mymap.scale_at(event.x, event.y, scale) self.draw_image() self.plot_origin() self.plot_waypoints() + self.canvas.scale("footprint", event.x, event.y, scale, scale) + self.canvas.scale("trajectory", event.x, event.y, scale, scale) self.message("Zoom Out") return """ + +++++ マウスホイールを回転したとき(タッチパッドをドラッグしたとき) +++++ + """ + def mouse_wheel(self, event): + if not self.mymap: return + if event.delta > 0: + scale = 1.1 # 上に回転(タッチパッドなら下にドラッグ)=> 拡大 + else: + scale = 0.9 # 下に回転(タッチパッドなら上にドラッグ)=> 縮小 + self.mymap.scale_at(event.x, event.y, scale) + self.draw_image() + self.plot_origin() + self.plot_waypoints() + self.canvas.scale("footprint", event.x, event.y, scale, scale) + self.canvas.scale("trajectory", event.x, event.y, scale, scale) + return + + + """ +++++ ウィンドウサイズが変更されたとき、情報を更新する +++++ """ def window_resize_callback(self, event): @@ -653,6 +1079,7 @@ self.canv_h = ch self.draw_image() return + @@ -673,6 +1100,7 @@ else: # 既に描画された画像を差し替える self.canvas.itemconfig("map_image", image=self.mymap.get_draw_image((self.canv_w, self.canv_h))) + self.canvas.tag_lower("map_image") return @@ -690,8 +1118,15 @@ """ def real2canvas(self, x, y): img_x, img_y = self.mymap.real2image(x,y) - real_x, real_y = self.mymap.transform(img_x, img_y) - return real_x, real_y + cx, cy = self.mymap.transform(img_x, img_y) + return round(cx), round(cy) + + + def update_title(self): + title = self.master.title() + if title[0] != "*": + self.master.title("* "+title) + @@ -702,4 +1137,8 @@ w, h = root.winfo_screenwidth()-10, root.winfo_screenheight()-100 root.geometry("%dx%d+0+0" % (w, h)) app = Application(master=root) # tk.Frameを継承したApplicationクラスのインスタンス - app.mainloop() + root.protocol("WM_DELETE_WINDOW", app.menu_exit) + try: + app.mainloop() + except KeyboardInterrupt as e: + app.menu_exit() diff --git a/src/waypoint_navigation/waypoint_manager/scripts/to_exe.bat b/src/waypoint_navigation/waypoint_manager/scripts/to_exe.bat new file mode 100644 index 0000000..30a7c4c --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/to_exe.bat @@ -0,0 +1,14 @@ +pyinstaller.exe manager_GUI.py --noconsole --noconfirm + +if exist .\waypoint_manager PowerShell -command " rm -r .\waypoint_manager " +PowerShell -command " mv .\dist\manager_GUI .\waypoint_manager " +PowerShell -command " rm -r .\build " +PowerShell -command " rm -r .\dist " +PowerShell -command " rm .\manager_GUI.spec " +PowerShell -command " cp -r .\icons .\waypoint_manager\ " + + + + + + diff --git a/src/waypoint_navigation/waypoint_manager/scripts/to_exe.sh b/src/waypoint_navigation/waypoint_manager/scripts/to_exe.sh new file mode 100755 index 0000000..00dddf8 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/scripts/to_exe.sh @@ -0,0 +1,13 @@ +python -m PyInstaller manager_GUI.py --noconsole --noconfirm + +if [ -d ./waypoint_manager ]; then + rm -r ./waypoint_manager +fi + +mv ./dist/manager_GUI ./waypoint_manager +rm -r ./build +rm -r ./dist +rm ./manager_GUI.spec +cp -r ./icons ./waypoint_manager/ + +# If the ModuleNotFoundError occur, copy the module from your environment diff --git a/src/waypoint_navigation/waypoint_manager/waypoint-manager-for-ubuntu.tar b/src/waypoint_navigation/waypoint_manager/waypoint-manager-for-ubuntu.tar new file mode 100644 index 0000000..d247cb0 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/waypoint-manager-for-ubuntu.tar Binary files differ diff --git a/src/waypoint_navigation/waypoint_manager/waypoint-manager-for-windows10.zip b/src/waypoint_navigation/waypoint_manager/waypoint-manager-for-windows10.zip new file mode 100644 index 0000000..48cd956 --- /dev/null +++ b/src/waypoint_navigation/waypoint_manager/waypoint-manager-for-windows10.zip Binary files differ diff --git a/src/waypoint_navigation/waypoint_nav/CMakeLists.txt b/src/waypoint_navigation/waypoint_nav/CMakeLists.txt index b4c1003..7a3d636 100644 --- a/src/waypoint_navigation/waypoint_nav/CMakeLists.txt +++ b/src/waypoint_navigation/waypoint_nav/CMakeLists.txt @@ -59,3 +59,9 @@ ${catkin_LIBRARIES} ) + +catkin_install_python(PROGRAMS + scripts/tandem_run_manager.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + diff --git a/src/waypoint_navigation/waypoint_nav/launch/waypoint_nav.launch b/src/waypoint_navigation/waypoint_nav/launch/waypoint_nav.launch old mode 100644 new mode 100755 index e7b5ece..654e341 --- a/src/waypoint_navigation/waypoint_nav/launch/waypoint_nav.launch +++ b/src/waypoint_navigation/waypoint_nav/launch/waypoint_nav.launch @@ -1,24 +1,38 @@ + - - - - - - + + + + + + + + + + - - - + + + + - - + + + + + + + + + + diff --git a/src/waypoint_navigation/waypoint_nav/maps/map.pgm b/src/waypoint_navigation/waypoint_nav/maps/map.pgm deleted file mode 100644 index 10700a1..0000000 --- a/src/waypoint_navigation/waypoint_nav/maps/map.pgm +++ /dev/null Binary files differ diff --git a/src/waypoint_navigation/waypoint_nav/maps/map.yaml b/src/waypoint_navigation/waypoint_nav/maps/map.yaml deleted file mode 100644 index 8cf0bd4..0000000 --- a/src/waypoint_navigation/waypoint_nav/maps/map.yaml +++ /dev/null @@ -1,7 +0,0 @@ -image: ./map.pgm -resolution: 0.050000 -origin: [-10.000000, -10.000000, 0.000000] -negate: 0 -occupied_thresh: 0.65 -free_thresh: 0.196 - diff --git a/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.pgm b/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.pgm deleted file mode 100644 index 8a70604..0000000 --- a/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.pgm +++ /dev/null Binary files differ diff --git a/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.yaml b/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.yaml deleted file mode 100644 index 27872d5..0000000 --- a/src/waypoint_navigation/waypoint_nav/maps/map_gakunai.yaml +++ /dev/null @@ -1,7 +0,0 @@ -image: map_gakunai.pgm -resolution: 0.050000 -origin: [-100.000000, -100.000000, 0.000000] -negate: 0 -occupied_thresh: 0.65 -free_thresh: 0.196 - diff --git a/src/waypoint_navigation/waypoint_nav/rviz_cfg/nav.rviz b/src/waypoint_navigation/waypoint_nav/rviz_cfg/nav.rviz index e0e7674..86336a2 100644 --- a/src/waypoint_navigation/waypoint_nav/rviz_cfg/nav.rviz +++ b/src/waypoint_navigation/waypoint_nav/rviz_cfg/nav.rviz @@ -5,7 +5,11 @@ Property Tree Widget: Expanded: ~ Splitter Ratio: 0.5 +<<<<<<< HEAD + Tree Height: 694 +======= Tree Height: 636 +>>>>>>> 21a0491cdbf23fb62e1951d64c737b70cdb8a9a8 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -342,17 +346,30 @@ Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 +<<<<<<< HEAD + Pitch: 0.904796838760376 + Target Frame: base_link + Yaw: 3.1003949642181396 +======= Pitch: 1.339796543121338 Target Frame: base_link Yaw: 3.1153953075408936 +>>>>>>> 21a0491cdbf23fb62e1951d64c737b70cdb8a9a8 Saved: ~ Window Geometry: Displays: collapsed: false +<<<<<<< HEAD + Height: 957 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd00000004000000000000019300000362fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e000002f3000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c0100000337000000690000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d00650100000000000004500000000000000000000004190000036200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 +======= Height: 897 Hide Left Dock: false Hide Right Dock: true QMainWindow State: 000000ff00000000fd00000004000000000000019300000326fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e000002b9000000cb00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000002200530074006100740065005400720069006700670065007200500061006e0065006c01000002fd000000670000004100ffffff000000010000010f000002b3fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003e000002b3000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005e00000003bfc0100000002fb0000000800540069006d00650000000000000005e00000039300fffffffb0000000800540069006d006501000000000000045000000000000000000000035c0000032600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 +>>>>>>> 21a0491cdbf23fb62e1951d64c737b70cdb8a9a8 Selection: collapsed: false StateTriggerPanel: @@ -363,6 +380,12 @@ collapsed: false Views: collapsed: true +<<<<<<< HEAD + Width: 1458 + X: 374 + Y: -40 +======= Width: 1269 X: 564 Y: -20 +>>>>>>> 21a0491cdbf23fb62e1951d64c737b70cdb8a9a8 diff --git a/src/waypoint_navigation/waypoint_nav/scripts/tandem_run_manager.py b/src/waypoint_navigation/waypoint_nav/scripts/tandem_run_manager.py new file mode 100755 index 0000000..7001f49 --- /dev/null +++ b/src/waypoint_navigation/waypoint_nav/scripts/tandem_run_manager.py @@ -0,0 +1,125 @@ +#!/usr/bin/env python3 + +import rospy +import dynamic_reconfigure.client +import ruamel.yaml +import numpy as np +from std_msgs.msg import UInt16 +from sensor_msgs.msg import LaserScan +from std_srvs.srv import Trigger + + +class TandemManager(): + + def __init__(self): + ## Read waypoints file + yaml = ruamel.yaml.YAML() + waypoints_path = rospy.get_param("tandem_run_manager/waypoints_file") + with open(waypoints_path) as file: + waypoints_yaml = yaml.load(file) + ## Register waypoint number of start/end tandem area + self.tandem_start_list = [] + self.tandem_end_list = [] + self.tandem_id = 0 + for i, data in enumerate(waypoints_yaml["waypoints"]): + if ("tandem_start" in data["point"]): + self.tandem_start_list.append(i+2) + if ("tandem_end" in data["point"]): + self.tandem_end_list.append(i+2) + self.no_tandem_area = (len(self.tandem_start_list) == 0) + ## Subscribers + self.wp_num_sub = rospy.Subscriber("/waypoint_num", UInt16, self.waypoint_num_callback) + self.scan_sub = rospy.Subscriber("/scan", LaserScan, self.laserscan_callback) + ## Waypoint navigation service clients + self.stop_nav = rospy.ServiceProxy("/stop_wp_nav", Trigger) + self.resume_nav = rospy.ServiceProxy("/resume_nav", Trigger) + ## Dynamic reconfigure clients + self.costmap_client1 = dynamic_reconfigure.client.Client("/move_base/global_costmap/obstacle_layer1") + self.costmap_client2 = dynamic_reconfigure.client.Client("/move_base/global_costmap/obstacle_layer2") + ## Variable + self.front_angle = 20 # degree + self.danger_dist = 1.2 # meter + self.waypoint_num = 0 + self.front_range = None + self.in_tandem_area = False + self.stop = False + return + + + ## Subscribe current waypoint number + def waypoint_num_callback(self, msg): + if (self.no_tandem_area) or (msg.data == self.waypoint_num) or (self.stop): return + if (self.waypoint_num == 0) and (msg.data > 1): + for i in range(0, len(self.tandem_start_list)): + if (msg.data >= self.tandem_end_list[i]): + self.tandem_id += 1 + continue + if (msg.data >= self.tandem_start_list[i]) and (msg.data < self.tandem_end_list[i]): + self.tandem_id = i + self.in_tandem_area = True + self.update_costmap_config(False) + rospy.loginfo("Enter tandem area.") + break + self.waypoint_num = msg.data + return + + if (msg.data == self.tandem_start_list[self.tandem_id]): + self.in_tandem_area = True + self.update_costmap_config(False) + rospy.loginfo("Enter tandem area.") + + elif (msg.data == self.tandem_end_list[self.tandem_id]): + self.in_tandem_area = False + self.update_costmap_config(True) + self.tandem_id += 1 + self.stop = (self.tandem_id >= len(self.tandem_start_list)) # if True, self.stop will never be False + rospy.loginfo("Exit from tandem area.") + + self.waypoint_num = msg.data + return + + + + def laserscan_callback(self, msg): + try: + if self.front_range is None: + front = round(-msg.angle_min / msg.angle_increment) + ran = int(round(np.deg2rad(self.front_angle/2) / msg.angle_increment)) + self.front_range = [front-ran, front+ran] + return + + if not self.in_tandem_area: return + ranges = np.array(msg.ranges[self.front_range[0]:self.front_range[1]]) + ## Use simply minimum + ranges[ranges <= msg.range_min] = msg.range_max + min_range = min(ranges) + ## or use sort + #sort_ranges = np.sort(ranges) + #min_range = np.mean(sort_ranges[:5]) + if (not self.stop) and (min_range < self.danger_dist): + self.stop_nav() + self.stop = True + rospy.loginfo("Stop because of obstacle within {}m ahead.".format(self.danger_dist)) + + elif (self.stop) and (min_range >= self.danger_dist+0.1): + self.resume_nav() + self.stop = False + rospy.loginfo("Resumed navigation because the obstacle ahead was more than {}m away.".format(self.danger_dist+0.1)) + + except AttributeError: + pass + return + + + def update_costmap_config(self, enable: bool): + self.costmap_client1.update_configuration({"enabled": enable}) + self.costmap_client2.update_configuration({"enabled": enable}) + return + + + + +if __name__ == '__main__': + rospy.init_node("map_changer") + tandem_manager = TandemManager() + rospy.spin() diff --git a/src/waypoint_navigation/waypoint_nav/src/velocity_controller.cpp b/src/waypoint_navigation/waypoint_nav/src/velocity_controller.cpp index 53735d7..d5a8406 100644 --- a/src/waypoint_navigation/waypoint_nav/src/velocity_controller.cpp +++ b/src/waypoint_navigation/waypoint_nav/src/velocity_controller.cpp @@ -27,8 +27,8 @@ ros::NodeHandle nh; max_vel_sub_ = nh.subscribe("/max_vel", 1, &VelocityController::maxVelCallback, this); - cmd_vel_sub_ = nh.subscribe("/cmd_vel_in", 10, &VelocityController::cmdVelCallback, this); - cmd_vel_pub_ = nh.advertise("/cmd_vel_out", 10); + cmd_vel_sub_ = nh.subscribe("/cmd_vel_in", 100, &VelocityController::cmdVelCallback, this); + cmd_vel_pub_ = nh.advertise("/cmd_vel_out", 100); nh.param(max_vel_param, standard_vel_, standard_vel_); nh.param(min_vel_param, min_vel_, min_vel_); @@ -76,4 +76,4 @@ ros::spin(); return 0; -} \ No newline at end of file +} diff --git a/src/waypoint_navigation/waypoint_nav/src/waypoint_nav.cpp b/src/waypoint_navigation/waypoint_nav/src/waypoint_nav.cpp old mode 100644 new mode 100755 index cb1f6e8..82c6e89 --- a/src/waypoint_navigation/waypoint_nav/src/waypoint_nav.cpp +++ b/src/waypoint_navigation/waypoint_nav/src/waypoint_nav.cpp @@ -12,6 +12,7 @@ #include #include #include +#include #include #include // include Waypoint class @@ -49,7 +50,9 @@ move_base_action_("move_base", true), rate_(10), last_moved_time_(0), - dist_err_(1.0) + dist_err_(1.0), + min_dist_err_(0.3), + min_yaw_err_(0.3) { while((move_base_action_.waitForServer(ros::Duration(1.0)) == false) && (ros::ok() == true)) { @@ -77,15 +80,26 @@ } else { ROS_ERROR("waypoints file doesn't have name"); } + + //Scripts of "start from the middle" + //Edited mori 2022/10/19 + //############################################################# + StartFromTheMiddle = false; + private_nh.getParam("StartFromTheMiddle", StartFromTheMiddle); + //############################################################# + + private_nh.param("min_dist_err", min_dist_err_, min_dist_err_); + private_nh.param("min_yaw_err", min_yaw_err_, min_yaw_err_); ros::NodeHandle nh; start_server_ = nh.advertiseService("start_wp_nav", &WaypointsNavigation::startNavigationCallback, this); stop_server_ = nh.advertiseService("stop_wp_nav", &WaypointsNavigation::stopNavigationCallback, this); resume_server_ = nh.advertiseService("resume_nav", &WaypointsNavigation::resumeNavigationCallback, this); cmd_vel_sub_ = nh.subscribe("cmd_vel", 1, &WaypointsNavigation::cmdVelCallback, this); + scan_sub_ = nh.subscribe("scan", 1, &WaypointsNavigation::laserscan_callback, this); wp_pub_ = nh.advertise("waypoints", 10); max_vel_pub_ = nh.advertise("max_vel", 5); - wp_num_pub_ = nh.advertise("waypoint_number", 5); + wp_num_pub_ = nh.advertise("waypoint_num", 5); clear_costmaps_srv_ = nh.serviceClient("/move_base/clear_costmaps"); } @@ -127,9 +141,15 @@ point.x = pose.position.x; point.y = pose.position.y; point.z = pose.position.z; - (*wp_node)[i]["point"]["vel"] >> point.vel; - (*wp_node)[i]["point"]["rad"] >> point.rad; - (*wp_node)[i]["point"]["stop"] >> point.stop; + try { + (*wp_node)[i]["point"]["vel"] >> point.vel; + } catch(...) {} // Use default value + try { + (*wp_node)[i]["point"]["rad"] >> point.rad; + } catch(...) {} + try { + (*wp_node)[i]["point"]["stop"] >> point.stop; + } catch(...) {} waypoint_list_.push_back(point); } } else { @@ -155,6 +175,7 @@ point.x = pose.position.x; point.y = pose.position.y; point.z = pose.position.z; + point.stop = true; waypoint_list_.push_back(point); } else { return false; @@ -197,16 +218,72 @@ response.success = false; return false; } + //Scripts of "start from the middle" + //Edited mori 2022/10/19 + //############################################################# + wp_num_.data = 1; + init_waypoint_ = waypoints_.poses.begin(); + compare_waypoint_ = waypoints_.poses.begin(); + double min_dist_w = std::numeric_limits::max(); + if(StartFromTheMiddle){ + ROS_INFO("StartFromTheMiddle => True"); + tf::StampedTransform robot_init_pos = getRobotPosGL(); + double init_x = robot_init_pos.getOrigin().x(); + double init_y = robot_init_pos.getOrigin().y(); + double pre_waypoint_x; + double pre_waypoint_y; + double convert_x; + double init_yaw = tf::getYaw(robot_init_pos.getRotation()); + double square_x; + double square_y; + double dist_w; + double dir_w; + int min_waypoint = 0; + int i = 0; + while(compare_waypoint_ != waypoints_.poses.end() - 1){ + i++; + square_x = (compare_waypoint_ -> position.x - init_x) * (compare_waypoint_ -> position.x - init_x); + square_y = (compare_waypoint_ -> position.y - init_y) * (compare_waypoint_ -> position.y - init_y); + dist_w = sqrt(square_x + square_y); + if(i == 1){ + dir_w = atan2(compare_waypoint_ -> position.y, compare_waypoint_ -> position.x); + convert_x = (compare_waypoint_ -> position.x - init_x) * cos(-init_yaw) - (compare_waypoint_ -> position.y - init_y) * sin(-init_yaw); + if(abs(dir_w - init_yaw) < (90 / 180.0 * M_PI) && convert_x > 0){ + min_dist_w = dist_w; + init_waypoint_ = compare_waypoint_; + min_waypoint = 1; + } + }else if(min_dist_w > dist_w){ + dir_w = atan2(compare_waypoint_ -> position.y - pre_waypoint_y, compare_waypoint_ -> position.x- pre_waypoint_x); + convert_x = (compare_waypoint_ -> position.x - init_x) * cos(-init_yaw) - (compare_waypoint_ -> position.y - init_y) * sin(-init_yaw); + if(abs(dir_w - init_yaw) < (90 / 180.0 * M_PI) && convert_x > 0){ + min_dist_w = dist_w; + init_waypoint_ = compare_waypoint_; + min_waypoint = i; + } + } + pre_waypoint_x = compare_waypoint_ -> position.x; + pre_waypoint_y = compare_waypoint_ -> position.y; + compare_waypoint_++; + } + wp_num_.data = min_waypoint; + } std_srvs::Empty empty; while(!clear_costmaps_srv_.call(empty)) { ROS_WARN("Resend clear costmap service"); sleep(); } - current_waypoint_ = waypoints_.poses.begin(); - wp_num_.data = 1; - has_activate_ = true; - response.success = true; - return true; + if(min_dist_w == std::numeric_limits::max()){ + ROS_WARN("Could not find the closest appropriate waypoint. Please check the direction of the robot again."); + response.success = false; + return false; + }else{ + current_waypoint_ = init_waypoint_; + has_activate_ = true; + response.success = true; + return true; + } + //############################################################# } @@ -220,6 +297,8 @@ ROS_WARN("Navigation is already active"); response.success = false; } else { + std_srvs::Empty empty; + clear_costmaps_srv_.call(empty); ROS_INFO("Navigation has resumed"); has_activate_ = true; response.success = true; @@ -228,7 +307,6 @@ } - /* ++++++++++ Callback function for service of "stop_wp_nav" ++++++++++ */ @@ -269,11 +347,121 @@ /* + ++++++++++ Callback function for /scan topic ++++++++++ + */ + void laserscan_callback(const sensor_msgs::LaserScan &msg) + { + laserscan = msg; + } + + + + /* + ++++++++++ Search for a goal without obstacles ++++++++++ + */ + void sendNoObstacleGoal(float first_thresh, float after_second_thresh, float goal_thresh, const geometry_msgs::Pose &dest) + { + if(laserscan.ranges.size() > 0){ + move_base_msgs::MoveBaseGoal move_base_goal; + tf::StampedTransform robot_pos = getRobotPosGL(); + geometry_msgs::Pose mid_waypoint; + double start_nav_time, time; + float sum_x, sum_y; + float x[laserscan.ranges.size()]; + float y[laserscan.ranges.size()]; + float waypoint_x = dest.position.x - robot_pos.getOrigin().x(); + float waypoint_y = dest.position.y - robot_pos.getOrigin().y(); + float robot_yaw = tf::getYaw(robot_pos.getRotation()); + float waypoint_x_update = dest.position.x - robot_pos.getOrigin().x(); + float waypoint_y_update = dest.position.y - robot_pos.getOrigin().y(); + float r = std::sqrt(std::pow(dest.position.x - robot_pos.getOrigin().x(), 2) + std::pow(dest.position.y - robot_pos.getOrigin().y(), 2)); + int j = 0; + int sum_num = 0; + bool pass_bool = false; + for(int i = 0; i < laserscan.ranges.size(); i++){ + if(!(laserscan.ranges[i] < laserscan.range_min || laserscan.ranges[i] > laserscan.range_max || std::isnan(laserscan.ranges[i]))){ + float theta = laserscan.angle_min + i * laserscan.angle_increment + robot_yaw; + x[j] = laserscan.ranges[i] * cosf(theta); + y[j] = laserscan.ranges[i] * sinf(theta); + j++; + } + } + float dist_waypoint[j]; + for(int i = 0;;i++){ + sum_x = 0; + sum_y = 0; + sum_num = 0; + for(int ii = 0; ii < j; ii++){ + dist_waypoint[ii] = std::sqrt(std::pow(x[ii] - waypoint_x_update, 2) + std::pow(y[ii] - waypoint_y_update, 2)); + if(i == 0 && dist_waypoint[ii] < first_thresh){ + sum_x += x[ii]; + sum_y += y[ii]; + sum_num++; + } + } + int size = sizeof(dist_waypoint) / sizeof(*dist_waypoint); + float min = *std::min_element(dist_waypoint, dist_waypoint + size); + if((i == 0 && min > first_thresh) || (i == 0 && std::sqrt(std::pow(waypoint_x_update, 2) + std::pow(waypoint_y_update, 2)) < first_thresh)){ + pass_bool = true; + ROS_WARN("Min dist_waypoint: %f", min); + ROS_WARN("Pass"); + break; + }else if(i == 0 && min < first_thresh){ + ROS_WARN("There is an obstacle near waypoint."); + ROS_WARN("Waypoint x: %f, y: %f", waypoint_x_update, waypoint_y_update); + ROS_WARN("Obstacle x: %f, y: %f", sum_x / sum_num, sum_y / sum_num); + }else if(waypoint_x * waypoint_x_update < 0){ + waypoint_x_update = waypoint_x; + waypoint_y_update = waypoint_y; + break; + }else if(i > 0 && min > after_second_thresh){ + break; + } + waypoint_x = waypoint_x_update; + waypoint_y = waypoint_y_update; + waypoint_x_update = (dest.position.x - robot_pos.getOrigin().x()) * (r - 0.5 * (i + 1)) / r; + waypoint_y_update = (dest.position.y - robot_pos.getOrigin().y()) * (r - 0.5 * (i + 1)) / r; + } + if(!pass_bool){ + std_srvs::Empty empty; + mid_waypoint.position.x = waypoint_x_update + robot_pos.getOrigin().x(); + mid_waypoint.position.y = waypoint_y_update + robot_pos.getOrigin().y(); + mid_waypoint.orientation = dest.orientation; + move_base_goal.target_pose.header.stamp = ros::Time::now(); + move_base_goal.target_pose.header.frame_id = world_frame_; + move_base_goal.target_pose.pose.orientation = mid_waypoint.orientation; + move_base_goal.target_pose.pose.position = mid_waypoint.position; + ROS_WARN("Send goal x: %f, y: %f", waypoint_x_update, waypoint_y_update); + move_base_action_.sendGoal(move_base_goal); + start_nav_time = ros::Time::now().toSec(); + while(!onNavigationPoint(mid_waypoint.position, goal_thresh)){ + time = ros::Time::now().toSec(); + if(time - start_nav_time > 10.0 && time - last_moved_time_ > 10.0) { + ROS_WARN("Resend the navigation goal."); + clear_costmaps_srv_.call(empty); + move_base_goal.target_pose.header.stamp = ros::Time::now(); + move_base_action_.sendGoal(move_base_goal); + start_nav_time = time; + } + sleep(); + } + ROS_WARN("Reach the goal without obstacle."); + } + } + } + + + + /* ++++++++++ Check if robot reached the goal sent to move_base ++++++++++ */ bool navigationFinished() { - return move_base_action_.getState() == actionlib::SimpleClientGoalState::SUCCEEDED; + if (move_base_action_.getState() == actionlib::SimpleClientGoalState::SUCCEEDED) { + ROS_WARN("Move base state is Goal reached"); + return true; + } + return false; } @@ -283,15 +471,22 @@ */ bool onNavigationPoint(const geometry_msgs::Point &dest, double dist_err=1.0) { - if (waypoint_list_[wp_num_.data-1].stop) { - return navigationFinished(); - } tf::StampedTransform robot_gl = getRobotPosGL(); const double wx = dest.x; const double wy = dest.y; const double rx = robot_gl.getOrigin().x(); const double ry = robot_gl.getOrigin().y(); const double dist = std::sqrt(std::pow(wx - rx, 2) + std::pow(wy - ry, 2)); + if (waypoint_list_[wp_num_.data-1].stop) { + tf::Quaternion q = robot_gl.getRotation(); + tf::Matrix3x3 m(q); + double r, p ,y; + m.getRPY(r, p, y); + double diff_yaw = std::abs(y - target_yaw_); + if ((dist < min_dist_err_) && (diff_yaw < min_yaw_err_)) return true; + else if ((dist < min_dist_err_ * 2) && navigationFinished()) return true; + return false; + } return dist < dist_err; } @@ -342,12 +537,27 @@ void startNavigationGL(const geometry_msgs::Pose &dest) { setMaxVel(); + bool FindGoalWithoutObstacle = true; + float first_thresh = 1.0; + float after_second_thresh = 1.0; + float goal_thresh = 0.5; + if(FindGoalWithoutObstacle){ + sendNoObstacleGoal(first_thresh, after_second_thresh, goal_thresh, dest); + } move_base_msgs::MoveBaseGoal move_base_goal; move_base_goal.target_pose.header.stamp = ros::Time::now(); move_base_goal.target_pose.header.frame_id = world_frame_; move_base_goal.target_pose.pose.position = dest.position; move_base_goal.target_pose.pose.orientation = dest.orientation; move_base_action_.sendGoal(move_base_goal); + sleep(); + if (waypoint_list_[wp_num_.data-1].stop) { + tf::Quaternion q(dest.orientation.x, dest.orientation.y, dest.orientation.z, dest.orientation.w); + tf::Matrix3x3 m(q); + double r, p ,y; + m.getRPY(r, p, y); + target_yaw_ = y; + } } @@ -370,6 +580,9 @@ void run() { ROS_INFO("Waiting for waypoint navigation to start."); + int resend_goal; + double start_nav_time, time; + std_srvs::Empty empty; while(ros::ok()) { // has_activate_ is false, nothing to do if (!has_activate_) { @@ -380,7 +593,17 @@ if (current_waypoint_ == finish_pose_) { ROS_INFO_STREAM("Go to final goal"); startNavigationGL(*current_waypoint_); - while(!navigationFinished() && ros::ok()) sleep(); + start_nav_time = ros::Time::now().toSec(); + while(!onNavigationPoint(finish_pose_->position) && ros::ok()) { + time = ros::Time::now().toSec(); + if (time - start_nav_time > 10.0 && time - last_moved_time_ > 10.0) { + ROS_WARN("Resend the navigation goal."); + clear_costmaps_srv_.call(empty); + startNavigationGL(*current_waypoint_); + start_nav_time = time; + } + sleep(); + } ROS_INFO("Final goal reached!!"); has_activate_ = false; continue; @@ -389,25 +612,20 @@ ROS_INFO_STREAM("Go to waypoint " << wp_num_.data); ROS_INFO_STREAM("x: " << waypoint_list_[wp_num_.data-1].x << ", y: " << waypoint_list_[wp_num_.data-1].y); startNavigationGL(*current_waypoint_); - int resend_goal = 0; - double start_nav_time = ros::Time::now().toSec(); + resend_goal = 0; + start_nav_time = ros::Time::now().toSec(); dist_err_ = waypoint_list_[wp_num_.data-1].rad; try { // loop until reach waypoint while(!onNavigationPoint(current_waypoint_->position, dist_err_)) { if (!has_activate_) throw SwitchRunningStatus(); - if ((!waypoint_list_[wp_num_.data-1].stop) && (navigationFinished())) { - ROS_WARN("Reached default yaw_goal_torelance."); - break; - } - double time = ros::Time::now().toSec(); + time = ros::Time::now().toSec(); if (time - start_nav_time > 10.0 && time - last_moved_time_ > 10.0) { ROS_WARN("Resend the navigation goal."); - std_srvs::Empty empty; clear_costmaps_srv_.call(empty); startNavigationGL(*current_waypoint_); resend_goal++; - if (resend_goal == 3) { + if (!waypoint_list_[wp_num_.data-1].stop && resend_goal == 3) { ROS_WARN("Skip waypoint."); break; } @@ -425,8 +643,10 @@ // update current waypoint current_waypoint_++; wp_num_.data++; + wp_num_pub_.publish(wp_num_); } catch(const SwitchRunningStatus &e) { + move_base_action_.cancelAllGoals(); ROS_INFO_STREAM("Running status switched"); } sleep(); @@ -441,6 +661,15 @@ geometry_msgs::PoseArray waypoints_; visualization_msgs::MarkerArray marker_; std::vector waypoint_list_; + + //Scripts of "start from the middle" + //Edited mori 2022/10/19 + //############################################################# + bool StartFromTheMiddle; + std::vector::iterator init_waypoint_; + std::vector::iterator compare_waypoint_; + //############################################################# + std::vector::iterator current_waypoint_; std::vector::iterator finish_pose_; bool has_activate_, stopped_; @@ -448,12 +677,13 @@ tf::TransformListener tf_listener_; ros::Rate rate_; ros::ServiceServer start_server_, stop_server_, resume_server_; - ros::Subscriber cmd_vel_sub_, move_base_status_sub_; + ros::Subscriber cmd_vel_sub_,scan_sub_, move_base_status_sub_; ros::Publisher wp_pub_, max_vel_pub_, wp_num_pub_; ros::ServiceClient clear_costmaps_srv_; - double last_moved_time_, dist_err_; + double last_moved_time_, dist_err_, min_dist_err_, target_yaw_, min_yaw_err_; std_msgs::UInt16 wp_num_; std_msgs::Float32 max_vel_msg_; + sensor_msgs::LaserScan laserscan; }; diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints.yaml index 92f70d6..d9fe6cb 100644 --- a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints.yaml +++ b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints.yaml @@ -1,10 +1,12 @@ waypoints: -- point: {x: -0.45, y: -0.499032, z: 0.0, vel: 1.0, rad: 0.3, stop: false} -- point: {x: 0.50, y: -0.576395, z: 0.0, vel: 0.5, rad: 0.1, stop: true} -- point: {x: 0.50, y: 0.80, z: 0.0, vel: 1.0, rad: 0.3, stop: false} -- point: {x: 0.515219, y: 1.8, z: 0.0, vel: 0.3, rad: 0.1, stop: true} +- point: {x: 1.0, y: 0.0, z: 0.0, vel: 0.5, rad: 1.0, stop: false} +- point: {x: 2.0, y: 0.0, z: 0.0, vel: 1.0, rad: 1.0, stop: true} +- point: {x: 3.0, y: 0.0, z: 0.0, vel: 1.0, rad: 0.5, stop: false} +- point: {x: 4.0, y: 0.0, z: 0.0, vel: 1.0, rad: 1.0, stop: false, tandem_start: 1} +- point: {x: 5.0, y: 0.0, z: 0.0, vel: 0.5, rad: 0.5, stop: false} +- point: {x: 6.0, y: 0.0, z: 0.0, vel: 0.5, rad: 0.5, stop: false, tandem_end: 1} finish_pose: - header: {seq: 0.0, stamp: 1620367430.3803937, frame_id: base_link} + header: {seq: 0, stamp: 113.132, frame_id: map} pose: - position: {x: -0.550981, y: 1.8, z: 0.0} - orientation: {x: 0.0, y: 0.0, z: 0.99749, w: 0.07074} \ No newline at end of file + position: {x: 7.0, y: 0.0, z: 0.0} + orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0} \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai.yaml deleted file mode 100644 index 1b42abe..0000000 --- a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai.yaml +++ /dev/null @@ -1,27 +0,0 @@ -waypoints: -- point: {x: 15.549, y: 1.99887, z: 0} -- point: {x: 27.7033, y: 0.740999, z: 0} -- point: {x: 44.367489, y: -3.73285, z: 0.0} -- point: {x: 53.4473, y: -1.98026, z: 0} -- point: {x: 53.5381, y: 13.9875, z: 0} -- point: {x: 53.0202, y: 25.7033, z: 0} -- point: {x: 52.624, y: 40.8326, z: 0} -- point: {x: 52.4651, y: 56.1678, z: 0} -- point: {x: 47.4651, y: 55.9678, z: 0} -- point: {x: 41.1833, y: 55.7508, z: 0} -- point: {x: 30.9773, y: 56.3972, z: 0} -- point: {x: 19.605, y: 55.9349, z: 0} -- point: {x: 9.74244, y: 57.775, z: 0} -- point: {x: 9.04664, y: 53.1814, z: 0} -- point: {x: 12.2474, y: 45.1187, z: 0} -- point: {x: 17.5568, y: 32.2592, z: 0} -- point: {x: 19.6331, y: 27.0299, z: 0} -- point: {x: 23.7635, y: 17.3945, z: 0} -- point: {x: 27.6797, y: 6.92171, z: 0} -- point: {x: 29.8247, y: 1.30448, z: 0} -- point: {x: 12.7818, y: 1.13019, z: 0} -finish_pose: - header: {seq: 0, stamp: 1623386648.025251, frame_id: base_link} - pose: - position: {x: -0.8863756, y: 0.5020624, z: 0} - orientation: {x: 0, y: 0, z: 0.999797, w: -0.0201511} \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai_edit.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai_edit.yaml deleted file mode 100644 index 5d13f3a..0000000 --- a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_gakunai_edit.yaml +++ /dev/null @@ -1,27 +0,0 @@ -waypoints: -- point: {x: 15.549, y: 1.99887, z: 0} -- point: {x: 27.7033, y: 0.740999, z: 0} -- point: {x: 44.5033, y: -3.88193, z: 0} -- point: {x: 53.4473, y: -1.98026, z: 0} -- point: {x: 53.5381, y: 13.9875, z: 0} -- point: {x: 53.0202, y: 25.7033, z: 0} -- point: {x: 52.624, y: 40.8326, z: 0} -- point: {x: 52.4651, y: 56.1678, z: 0} -- point: {x: 47.4651, y: 55.9678, z: 0} -- point: {x: 41.1833, y: 55.7508, z: 0} -- point: {x: 30.9773, y: 56.3972, z: 0} -- point: {x: 19.605, y: 55.9349, z: 0} -- point: {x: 9.74244, y: 57.775, z: 0} -- point: {x: 9.04664, y: 53.1814, z: 0} -- point: {x: 12.2474, y: 45.1187, z: 0} -- point: {x: 17.5568, y: 32.2592, z: 0} -- point: {x: 19.6331, y: 27.0299, z: 0} -- point: {x: 23.7635, y: 17.3945, z: 0} -- point: {x: 27.6797, y: 6.92171, z: 0} -- point: {x: 29.8247, y: 1.30448, z: 0} -- point: {x: 12.7818, y: 1.13019, z: 0} -finish_pose: - header: {seq: 0, stamp: 1623386648.025251, frame_id: base_link} - pose: - position: {x: -0.8863756, y: 0.5020624, z: 0} - orientation: {x: 0, y: 0, z: 0.999797, w: -0.0201511} \ No newline at end of file diff --git a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_test.yaml b/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_test.yaml deleted file mode 100644 index 713cc07..0000000 --- a/src/waypoint_navigation/waypoint_nav/waypoints_cfg/waypoints_test.yaml +++ /dev/null @@ -1,13 +0,0 @@ -waypoints: -- point: {x: -1.01321, y: -0.528956, z: -0.000870705, vel: 1, rad: 0.8, stop: 0} -- point: {x: -0.0284393, y: -0.471859, z: 0.00520468, vel: 1, rad: 0.8, stop: 0} -- point: {x: 0.981428, y: -0.5452, z: 0.00261879, vel: 1, rad: 0.8, stop: 0} -- point: {x: 1.90456, y: -0.536331, z: 0.00246334, vel: 1, rad: 0.8, stop: 0} -- point: {x: 1.95224, y: 0.538929, z: 0.00476408, vel: 1, rad: 0.8, stop: 0} -- point: {x: 0.603558, y: 0.551442, z: 0.00079298, vel: 1, rad: 0.8, stop: 0} -- point: {x: 0.539775, y: 1.787, z: 0.00275993, vel: 1, rad: 0.8, stop: 0} -finish_pose: - header: {seq: 0, stamp: 244.465000000, frame_id: map} - pose: - position: {x: -0.488029, y: 1.82672, z: 0} - orientation: {x: 0, y: 0, z: 0.999992, w: 0.00399584} diff --git a/src/waypoint_navigation/waypoint_saver/launch/waypoint_saver.launch b/src/waypoint_navigation/waypoint_saver/launch/waypoint_saver.launch index 9873494..023a6d0 100644 --- a/src/waypoint_navigation/waypoint_saver/launch/waypoint_saver.launch +++ b/src/waypoint_navigation/waypoint_saver/launch/waypoint_saver.launch @@ -4,10 +4,10 @@ - + - + diff --git a/src/zlac8015d_ros/README.md b/src/zlac8015d_ros/README.md index d38891e..376b0ff 100644 --- a/src/zlac8015d_ros/README.md +++ b/src/zlac8015d_ros/README.md @@ -1,7 +1,7 @@ # ROS package for ZLAC8015D dual-channel servo driver [![](https://img.shields.io/badge/ROS-Noetic-brightgreen.svg)](https://github.com/Alpaca-zip/zlac8015d_ros) - +![circuit_scheme](https://user-images.githubusercontent.com/84959376/191182537-47d49329-7e61-4c6c-b6a7-7eab8f530f07.png) ## 1 Installation ``` @@ -11,25 +11,33 @@ $ cd .. && catkin_make ``` - -## 2 Change full pathname of parameter file -`scripts/motor_driver_node.py` refers to `/home/ubuntu/catkin_ws/src/zlac8015d_ros/params/motor_driver_params.yaml` as default. -If you want to specify a different full pathname, change line 34 in `scripts/motor_driver_node.py` - -## 3 Usage +## 2 Usage ### Run motor_driver_node ``` -$ rosrun zlac8015d_ros motor_driver_node.py +$ roslaunch zlac8015d_ros motor_driver_node.launch ``` ### Parameters - `port`: Name of the zlac8015d port. Default is `dev/ttyUSB0`. -- `travel_in_one_rev`: Tire circumference. Default is `0.655`[m]. -- `R_Wheel`: Tire radius. Default is `0.105`[m]. -- `cpr`: CPR(Counts Per Revolution). Default is `16385`. -- `wheels_base_width`: Distance between tires. Default is `0.440`[m]. - `control_mode`: `1` is relative position control mode, `3` is speed rpm control mode. Default is `3`. +- `debug`: If `true`, odometry information is displayed. Default is `false`. +- `twist_cmd_vel_topic`: Topic name for Twist-type messages. Default is `/zlac8015d/twist/cmd_vel`. +- `cmd_vel_topic`: Topic name for cmd_vel[m/s] messages. Default is `/zlac8015d/vel/cmd_vel`. +- `cmd_rpm_topic`: Topic name for cmd_rpm messages. Default is `/zlac8015d/vel/cmd_rpm`. +- `cmd_deg_topic`: Topic name for cmd_deg[°] messages. Default is `/zlac8015d/pos/cmd_deg`. +- `cmd_dist_topic`: Topic name for cmd_dist[m] messages. Default is `/zlac8015d/pos/cmd_dist`. +- `publish_TF`: If `true`, TF is published. Default is `true`. +- `TF_header_frame`: Name of the TF header frame. Default is `odom`. +- `TF_child_frame`: Name of the TF child frame. Default is `base_link`. +- `publish_odom`: If `true`, `/odom` is published. Default is `true`. +- `odom_header_frame`: Name of the odometry header frame. Default is `odom`. +- `odom_child_frame`: Name of the odometry child frame. Default is `base_link`. +- `left_wheel_radius`: Left wheel radius. Default is `0.1015`[m]. +- `right_wheel_radius`: Right wheel radius. Default is `0.1015`[m]. +- `computation_left_wheel_radius`: Radius of left wheel used for odometry computation. Default is `0.1015`[m]. +- `computation_right_wheel_radius`: Radius of right wheel used for odometry computation. Default is `0.1015`[m]. +- `cpr`: CPR(Counts Per Revolution). Default is `16385`. +- `wheels_base_width`: Distance between tires. Default is `0.5668`[m]. - `callback_timeout`: Motor automatically stops if no topics are received for a certain period of time. Default is `0.5`[s]. -- `decimil_coefficient`: Must be specified in digits. Smaller values will cause small changes in tire motion to have a greater impact on the odometry calculations. `0.01` or `0.001` is highly recommended. Default is `0.001`. - `set_accel_time_left`: Acceleration time for left tire. Default is `200`[ms]. - `set_accel_time_right`: Acceleration time for right tire. Default is `200`[ms]. - `set_decel_time_left`: Deceleration time for left tire. Default is `200`[ms]. @@ -37,10 +45,6 @@ - `max_left_rpm`: Maximum rpm of left tire. Default is `150`. - `max_right_rpm`: Maximum rpm of right tire. Default is `150`. - `deadband_rpm`: Width of rpm to be regarded as 0. If `3`, then -3 to 3 is considered rpm 0. Default is `3`. -- `TF_header_frame`: Header frame of TF. Default is `odom`. -- `TF_child_frame`: Child frame of TF. Default is `base_link`. -- `odom_header_frame`: Header frame of odom. Default is `odom`. -- `odom_child_frame`: Child frame of odom. Default is `base_link`. ### Topics This node publishes the following topics. @@ -53,3 +57,9 @@ - `/zlac8015d/vel/cmd_rpm`: Send command as rpm in speed rpm control, e.g. [100, 50] 100 rpm of left wtire, 50 rpm of right tire. - `/zlac8015d/pos/deg_cmd`: Send command as angle degree in position control, e.g. [90,70] 90 [deg] of left tire, 70 [deg] of right tire. - `/zlac8015d/pos/dist_cmd`: Send command as desired travelling distance in position control, e.g. [1.0, 1.0] for 1[m] travelling distance of each tire. +- `/estop`: Send command as emergency stop signal, e.g. true for emergency stop is activated. + +### Emergency stop Feature +The motor is locked when you publish a `true` message on the `/estop` topic. + +This feature is not recommended. Emergency stop should be controlled by hardware. diff --git a/src/zlac8015d_ros/circuit_scheme.png b/src/zlac8015d_ros/circuit_scheme.png deleted file mode 100644 index 04897a1..0000000 --- a/src/zlac8015d_ros/circuit_scheme.png +++ /dev/null Binary files differ diff --git a/src/zlac8015d_ros/emergency_stop/emergency_stop.ino b/src/zlac8015d_ros/emergency_stop/emergency_stop.ino deleted file mode 100644 index e8ad546..0000000 --- a/src/zlac8015d_ros/emergency_stop/emergency_stop.ino +++ /dev/null @@ -1,109 +0,0 @@ -/* -Copyright (C) 2022 Alpaca-zip - -This program is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program. If not, see . - -%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% - -For the emergency stop to work correctly, you will need to: - -1, Edit ModbusMaster.h - -2, Line 252: static const uint16_t ku16MBResponseTimeout = 2000; => static const uint16_t ku16MBResponseTimeout = 100; -*/ - -#include -#define MAX485_DE 3 -#define MAX485_RE_NEG 2 - -ModbusMaster node; // instantiate ModbusMaster object - -// set pin numbers: -const int estop_buttonPin = 7; // the number of the estop button pin -const int reset_buttonPin = 8; // the number of the reset button pin -const int ledPin = 13; // the number of the LED pin -int estop_buttonState = 0; // variable for reading the estop button status -int reset_buttonState = 0; // variable for reading the reset button status -bool estop_flag; // flag for emer_stop() -bool reset_flag; // flag for reset() - -void preTransmission(){ - digitalWrite(MAX485_RE_NEG, 1); - digitalWrite(MAX485_DE, 1); -} - -void postTransmission(){ - digitalWrite(MAX485_RE_NEG, 0); - digitalWrite(MAX485_DE, 0); -} - -void emer_stop(){ - uint8_t estop_response; - while(estop_flag){ - estop_response = node.writeSingleRegister(0x200E, 0x05); // 0x05: emergency stop - if(estop_response == 0){ - digitalWrite(ledPin, HIGH); // turn LED on - estop_flag = false; - reset_flag = true; - } - } -} - -void reset(){ - uint8_t reset_response; - while(reset_flag){ - reset_response = node.writeSingleRegister(0x200E, 0x06); // 0x06: clear fault - if(reset_response == 0) continue; - reset_response = node.writeSingleRegister(0x200E, 0x07); // 0x07: stop - if(reset_response == 0) continue; - reset_response = node.writeSingleRegister(0x200E, 0x08); // 0x08: enable - if(reset_response == 0){ - digitalWrite(ledPin, LOW); // turn LED off - estop_flag = true; - reset_flag = false; - } - } -} - -void setup(){ - pinMode(ledPin, OUTPUT); // initialize the LED pin as an output: - pinMode(estop_buttonPin, INPUT_PULLUP); // initialize the estop button pin as an input - pinMode(reset_buttonPin, INPUT_PULLUP); // initialize the reset button pin as an input - pinMode(MAX485_RE_NEG, OUTPUT); // initialize the MAX485_RE_NEG pin as an output - pinMode(MAX485_DE, OUTPUT); // initialize the MAX485_DE pin as an output - - // Init in receive mode - digitalWrite(MAX485_RE_NEG, 0); - digitalWrite(MAX485_DE, 0); - - Serial.begin(115200); // modbus communication runs at 115200 baud - node.begin(1, Serial); // modbus slave ID 1 - // callbacks allow us to configure the RS485 transceiver correctly - node.preTransmission(preTransmission); - node.postTransmission(postTransmission); - - estop_flag = true; // initialize the flag as a TRUE - reset_flag = false; // initialize the flag as a FALSE -} - -void loop(){ - estop_buttonState = digitalRead(estop_buttonPin); // read the state of the estop_buttonPin value - reset_buttonState = digitalRead(reset_buttonPin); // read the state of the reset_buttonPin value - - if(estop_buttonState == LOW){ // estop button is pressed - emer_stop(); - }else if(reset_buttonState == LOW){ // reset button is pressed - reset(); - } -} diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/emergency_stop.fzz b/src/zlac8015d_ros/emergency_stop/module_PCB/emergency_stop.fzz deleted file mode 100644 index b2e7678..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/emergency_stop.fzz +++ /dev/null Binary files differ diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_contour.gm1 b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_contour.gm1 deleted file mode 100644 index 367d0be..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_contour.gm1 +++ /dev/null @@ -1,26 +0,0 @@ -G04 MADE WITH FRITZING* -G04 WWW.FRITZING.ORG* -G04 DOUBLE SIDED* -G04 HOLES PLATED* -G04 CONTOUR ON CENTER OF CONTOUR VECTOR* -%ASAXBY*% -%FSLAX23Y23*% -%MOIN*% -%OFA0B0*% -%SFA1.0B1.0*% -%ADD10R,2.602410X1.799010*% -%ADD11C,0.008000*% -%ADD10C,0.008*% -%LNCONTOUR*% -G90* -G70* -G54D10* -G54D11* -X4Y1795D02* -X2598Y1795D01* -X2598Y4D01* -X4Y4D01* -X4Y1795D01* -D02* -G04 End of contour* -M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperBottom.gbl b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperBottom.gbl deleted file mode 100644 index ef253af..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperBottom.gbl +++ /dev/null @@ -1,4775 +0,0 @@ -G04 MADE WITH FRITZING* -G04 WWW.FRITZING.ORG* -G04 DOUBLE SIDED* -G04 HOLES PLATED* -G04 CONTOUR ON CENTER OF CONTOUR VECTOR* -%ASAXBY*% -%FSLAX23Y23*% -%MOIN*% -%OFA0B0*% -%SFA1.0B1.0*% -%ADD10C,0.075000*% -%ADD11C,0.070000*% -%ADD12C,0.078000*% -%ADD13R,0.069972X0.070000*% -%ADD14C,0.024000*% -%LNCOPPER0*% -G90* -G70* -G54D10* -X1491Y1416D03* -X423Y1693D03* -X683Y974D03* -X1003Y1128D03* -G54D11* -X1699Y1599D03* -X1699Y1499D03* -X1699Y1399D03* -X1699Y1299D03* -X1699Y1199D03* -X1699Y1099D03* -X1699Y999D03* -X1699Y899D03* -X1699Y799D03* -X1699Y699D03* -X1699Y599D03* -X1699Y499D03* -X1699Y399D03* -X1699Y299D03* -X1699Y199D03* -X2299Y1599D03* -X2299Y1499D03* -X2299Y1399D03* -X2299Y1299D03* -X2299Y1199D03* -X2299Y1099D03* -X2299Y999D03* -X2299Y899D03* -X2299Y799D03* -X2299Y699D03* -X2299Y599D03* -X2299Y499D03* -X2299Y399D03* -X2299Y299D03* -X2299Y199D03* -G54D12* -X1199Y1699D03* -X1299Y1699D03* -X1399Y1699D03* -X1499Y1699D03* -X1199Y99D03* -X1299Y99D03* -X1399Y99D03* -X1499Y99D03* -X399Y1099D03* -X499Y1099D03* -X599Y1099D03* -X699Y1099D03* -X799Y1099D03* -X899Y1099D03* -X299Y1699D03* -X299Y1599D03* -X999Y1699D03* -X999Y1599D03* -G54D13* -X1699Y1599D03* -G54D14* -X1397Y1199D02* -X1681Y1199D01* -D02* -X1399Y1680D02* -X1397Y1199D01* -D02* -X1299Y1100D02* -X1299Y1680D01* -D02* -X1681Y1099D02* -X1299Y1100D01* -D02* -X1500Y1500D02* -X1681Y1499D01* -D02* -X1499Y1680D02* -X1500Y1500D01* -D02* -X1799Y1600D02* -X1717Y1599D01* -D02* -X1799Y100D02* -X1799Y1600D01* -D02* -X1198Y1198D02* -X198Y1198D01* -D02* -X198Y1198D02* -X198Y399D01* -D02* -X198Y399D02* -X1600Y399D01* -D02* -X1600Y399D02* -X1600Y100D01* -D02* -X1600Y100D02* -X1799Y100D01* -D02* -X1199Y1680D02* -X1198Y1198D01* -D02* -X599Y598D02* -X1681Y599D01* -D02* -X599Y1080D02* -X599Y598D01* -D02* -X800Y697D02* -X1681Y699D01* -D02* -X799Y1080D02* -X800Y697D01* -G36* -X1338Y1671D02* -X1338Y1669D01* -X1336Y1669D01* -X1336Y1665D01* -X1334Y1665D01* -X1334Y1663D01* -X1330Y1663D01* -X1330Y1661D01* -X1328Y1661D01* -X1328Y1659D01* -X1326Y1659D01* -X1326Y1657D01* -X1322Y1657D01* -X1322Y1477D01* -X1320Y1477D01* -X1320Y1123D01* -X1424Y1123D01* -X1424Y1121D01* -X1660Y1121D01* -X1660Y1123D01* -X1662Y1123D01* -X1662Y1125D01* -X1664Y1125D01* -X1664Y1127D01* -X1666Y1127D01* -X1666Y1131D01* -X1668Y1131D01* -X1668Y1133D01* -X1672Y1133D01* -X1672Y1135D01* -X1674Y1135D01* -X1674Y1137D01* -X1678Y1137D01* -X1678Y1139D01* -X1680Y1139D01* -X1680Y1159D01* -X1678Y1159D01* -X1678Y1161D01* -X1674Y1161D01* -X1674Y1163D01* -X1672Y1163D01* -X1672Y1165D01* -X1668Y1165D01* -X1668Y1167D01* -X1666Y1167D01* -X1666Y1171D01* -X1664Y1171D01* -X1664Y1173D01* -X1662Y1173D01* -X1662Y1175D01* -X1660Y1175D01* -X1660Y1177D01* -X1392Y1177D01* -X1392Y1179D01* -X1386Y1179D01* -X1386Y1181D01* -X1384Y1181D01* -X1384Y1183D01* -X1382Y1183D01* -X1382Y1185D01* -X1380Y1185D01* -X1380Y1187D01* -X1378Y1187D01* -X1378Y1191D01* -X1376Y1191D01* -X1376Y1633D01* -X1378Y1633D01* -X1378Y1655D01* -X1376Y1655D01* -X1376Y1657D01* -X1372Y1657D01* -X1372Y1659D01* -X1370Y1659D01* -X1370Y1661D01* -X1368Y1661D01* -X1368Y1663D01* -X1366Y1663D01* -X1366Y1665D01* -X1364Y1665D01* -X1364Y1667D01* -X1362Y1667D01* -X1362Y1669D01* -X1360Y1669D01* -X1360Y1671D01* -X1338Y1671D01* -G37* -D02* -G36* -X1438Y1671D02* -X1438Y1669D01* -X1436Y1669D01* -X1436Y1665D01* -X1434Y1665D01* -X1434Y1663D01* -X1430Y1663D01* -X1430Y1661D01* -X1428Y1661D01* -X1428Y1659D01* -X1426Y1659D01* -X1426Y1657D01* -X1422Y1657D01* -X1422Y1629D01* -X1420Y1629D01* -X1420Y1221D01* -X1660Y1221D01* -X1660Y1223D01* -X1662Y1223D01* -X1662Y1225D01* -X1664Y1225D01* -X1664Y1227D01* -X1666Y1227D01* -X1666Y1231D01* -X1668Y1231D01* -X1668Y1233D01* -X1672Y1233D01* -X1672Y1235D01* -X1674Y1235D01* -X1674Y1237D01* -X1678Y1237D01* -X1678Y1239D01* -X1680Y1239D01* -X1680Y1259D01* -X1678Y1259D01* -X1678Y1261D01* -X1674Y1261D01* -X1674Y1263D01* -X1672Y1263D01* -X1672Y1265D01* -X1668Y1265D01* -X1668Y1267D01* -X1666Y1267D01* -X1666Y1271D01* -X1664Y1271D01* -X1664Y1273D01* -X1662Y1273D01* -X1662Y1275D01* -X1660Y1275D01* -X1660Y1279D01* -X1658Y1279D01* -X1658Y1285D01* -X1656Y1285D01* -X1656Y1291D01* -X1654Y1291D01* -X1654Y1307D01* -X1656Y1307D01* -X1656Y1313D01* -X1658Y1313D01* -X1658Y1319D01* -X1660Y1319D01* -X1660Y1323D01* -X1662Y1323D01* -X1662Y1325D01* -X1664Y1325D01* -X1664Y1327D01* -X1666Y1327D01* -X1666Y1331D01* -X1668Y1331D01* -X1668Y1333D01* -X1672Y1333D01* -X1672Y1335D01* -X1674Y1335D01* -X1674Y1337D01* -X1678Y1337D01* -X1678Y1339D01* -X1680Y1339D01* -X1680Y1359D01* -X1678Y1359D01* -X1678Y1361D01* -X1674Y1361D01* -X1674Y1363D01* -X1672Y1363D01* -X1672Y1365D01* -X1668Y1365D01* -X1668Y1367D01* -X1666Y1367D01* -X1666Y1371D01* -X1664Y1371D01* -X1664Y1373D01* -X1662Y1373D01* -X1662Y1375D01* -X1660Y1375D01* -X1660Y1379D01* -X1658Y1379D01* -X1658Y1385D01* -X1656Y1385D01* -X1656Y1391D01* -X1654Y1391D01* -X1654Y1407D01* -X1656Y1407D01* -X1656Y1413D01* -X1658Y1413D01* -X1658Y1419D01* -X1660Y1419D01* -X1660Y1423D01* -X1662Y1423D01* -X1662Y1425D01* -X1664Y1425D01* -X1664Y1427D01* -X1666Y1427D01* -X1666Y1431D01* -X1668Y1431D01* -X1668Y1433D01* -X1672Y1433D01* -X1672Y1435D01* -X1674Y1435D01* -X1674Y1437D01* -X1678Y1437D01* -X1678Y1439D01* -X1680Y1439D01* -X1680Y1459D01* -X1678Y1459D01* -X1678Y1461D01* -X1674Y1461D01* -X1674Y1463D01* -X1672Y1463D01* -X1672Y1465D01* -X1668Y1465D01* -X1668Y1467D01* -X1666Y1467D01* -X1666Y1471D01* -X1664Y1471D01* -X1664Y1473D01* -X1662Y1473D01* -X1662Y1475D01* -X1660Y1475D01* -X1660Y1477D01* -X1498Y1477D01* -X1498Y1479D01* -X1490Y1479D01* -X1490Y1481D01* -X1488Y1481D01* -X1488Y1483D01* -X1484Y1483D01* -X1484Y1487D01* -X1482Y1487D01* -X1482Y1489D01* -X1480Y1489D01* -X1480Y1493D01* -X1478Y1493D01* -X1478Y1655D01* -X1476Y1655D01* -X1476Y1657D01* -X1472Y1657D01* -X1472Y1659D01* -X1470Y1659D01* -X1470Y1661D01* -X1468Y1661D01* -X1468Y1663D01* -X1466Y1663D01* -X1466Y1665D01* -X1464Y1665D01* -X1464Y1667D01* -X1462Y1667D01* -X1462Y1669D01* -X1460Y1669D01* -X1460Y1671D01* -X1438Y1671D01* -G37* -D02* -G36* -X132Y1759D02* -X132Y1739D01* -X136Y1739D01* -X136Y1737D01* -X138Y1737D01* -X138Y1735D01* -X140Y1735D01* -X140Y1731D01* -X142Y1731D01* -X142Y1729D01* -X144Y1729D01* -X144Y1725D01* -X146Y1725D01* -X146Y1721D01* -X148Y1721D01* -X148Y1717D01* -X150Y1717D01* -X150Y1711D01* -X152Y1711D01* -X152Y1687D01* -X150Y1687D01* -X150Y1681D01* -X148Y1681D01* -X148Y1677D01* -X146Y1677D01* -X146Y1673D01* -X144Y1673D01* -X144Y1669D01* -X142Y1669D01* -X142Y1667D01* -X140Y1667D01* -X140Y1663D01* -X138Y1663D01* -X138Y1661D01* -X136Y1661D01* -X136Y1659D01* -X132Y1659D01* -X132Y1657D01* -X130Y1657D01* -X130Y1655D01* -X128Y1655D01* -X128Y1653D01* -X124Y1653D01* -X124Y1651D01* -X120Y1651D01* -X120Y1649D01* -X114Y1649D01* -X114Y1647D01* -X104Y1647D01* -X104Y1645D01* -X272Y1645D01* -X272Y1659D01* -X270Y1659D01* -X270Y1661D01* -X268Y1661D01* -X268Y1663D01* -X266Y1663D01* -X266Y1665D01* -X264Y1665D01* -X264Y1667D01* -X262Y1667D01* -X262Y1669D01* -X260Y1669D01* -X260Y1671D01* -X258Y1671D01* -X258Y1675D01* -X256Y1675D01* -X256Y1679D01* -X254Y1679D01* -X254Y1683D01* -X252Y1683D01* -X252Y1691D01* -X250Y1691D01* -X250Y1707D01* -X252Y1707D01* -X252Y1715D01* -X254Y1715D01* -X254Y1719D01* -X256Y1719D01* -X256Y1723D01* -X258Y1723D01* -X258Y1727D01* -X260Y1727D01* -X260Y1729D01* -X262Y1729D01* -X262Y1731D01* -X264Y1731D01* -X264Y1733D01* -X266Y1733D01* -X266Y1735D01* -X268Y1735D01* -X268Y1737D01* -X270Y1737D01* -X270Y1739D01* -X272Y1739D01* -X272Y1759D01* -X132Y1759D01* -G37* -D02* -G36* -X326Y1759D02* -X326Y1739D01* -X328Y1739D01* -X328Y1737D01* -X332Y1737D01* -X332Y1735D01* -X334Y1735D01* -X334Y1733D01* -X336Y1733D01* -X336Y1729D01* -X338Y1729D01* -X338Y1727D01* -X340Y1727D01* -X340Y1725D01* -X342Y1725D01* -X342Y1721D01* -X344Y1721D01* -X344Y1717D01* -X346Y1717D01* -X346Y1709D01* -X348Y1709D01* -X348Y1689D01* -X346Y1689D01* -X346Y1681D01* -X344Y1681D01* -X344Y1677D01* -X342Y1677D01* -X342Y1673D01* -X340Y1673D01* -X340Y1671D01* -X338Y1671D01* -X338Y1669D01* -X336Y1669D01* -X336Y1665D01* -X334Y1665D01* -X334Y1663D01* -X330Y1663D01* -X330Y1661D01* -X328Y1661D01* -X328Y1659D01* -X326Y1659D01* -X326Y1639D01* -X328Y1639D01* -X328Y1637D01* -X332Y1637D01* -X332Y1635D01* -X334Y1635D01* -X334Y1633D01* -X336Y1633D01* -X336Y1629D01* -X338Y1629D01* -X338Y1627D01* -X340Y1627D01* -X340Y1625D01* -X342Y1625D01* -X342Y1621D01* -X344Y1621D01* -X344Y1617D01* -X346Y1617D01* -X346Y1609D01* -X348Y1609D01* -X348Y1589D01* -X346Y1589D01* -X346Y1581D01* -X344Y1581D01* -X344Y1577D01* -X342Y1577D01* -X342Y1573D01* -X340Y1573D01* -X340Y1571D01* -X338Y1571D01* -X338Y1569D01* -X336Y1569D01* -X336Y1565D01* -X334Y1565D01* -X334Y1563D01* -X330Y1563D01* -X330Y1561D01* -X328Y1561D01* -X328Y1559D01* -X326Y1559D01* -X326Y1557D01* -X322Y1557D01* -X322Y1555D01* -X318Y1555D01* -X318Y1553D01* -X312Y1553D01* -X312Y1551D01* -X986Y1551D01* -X986Y1553D01* -X980Y1553D01* -X980Y1555D01* -X976Y1555D01* -X976Y1557D01* -X972Y1557D01* -X972Y1559D01* -X970Y1559D01* -X970Y1561D01* -X968Y1561D01* -X968Y1563D01* -X966Y1563D01* -X966Y1565D01* -X964Y1565D01* -X964Y1567D01* -X962Y1567D01* -X962Y1569D01* -X960Y1569D01* -X960Y1571D01* -X958Y1571D01* -X958Y1575D01* -X956Y1575D01* -X956Y1579D01* -X954Y1579D01* -X954Y1583D01* -X952Y1583D01* -X952Y1591D01* -X950Y1591D01* -X950Y1607D01* -X952Y1607D01* -X952Y1615D01* -X954Y1615D01* -X954Y1619D01* -X956Y1619D01* -X956Y1623D01* -X958Y1623D01* -X958Y1627D01* -X960Y1627D01* -X960Y1629D01* -X962Y1629D01* -X962Y1631D01* -X964Y1631D01* -X964Y1633D01* -X966Y1633D01* -X966Y1635D01* -X968Y1635D01* -X968Y1637D01* -X970Y1637D01* -X970Y1639D01* -X972Y1639D01* -X972Y1659D01* -X970Y1659D01* -X970Y1661D01* -X968Y1661D01* -X968Y1663D01* -X966Y1663D01* -X966Y1665D01* -X964Y1665D01* -X964Y1667D01* -X962Y1667D01* -X962Y1669D01* -X960Y1669D01* -X960Y1671D01* -X958Y1671D01* -X958Y1675D01* -X956Y1675D01* -X956Y1679D01* -X954Y1679D01* -X954Y1683D01* -X952Y1683D01* -X952Y1691D01* -X950Y1691D01* -X950Y1707D01* -X952Y1707D01* -X952Y1715D01* -X954Y1715D01* -X954Y1719D01* -X956Y1719D01* -X956Y1723D01* -X958Y1723D01* -X958Y1727D01* -X960Y1727D01* -X960Y1729D01* -X962Y1729D01* -X962Y1731D01* -X964Y1731D01* -X964Y1733D01* -X966Y1733D01* -X966Y1735D01* -X968Y1735D01* -X968Y1737D01* -X970Y1737D01* -X970Y1739D01* -X972Y1739D01* -X972Y1759D01* -X326Y1759D01* -G37* -D02* -G36* -X1026Y1759D02* -X1026Y1739D01* -X1028Y1739D01* -X1028Y1737D01* -X1032Y1737D01* -X1032Y1735D01* -X1034Y1735D01* -X1034Y1733D01* -X1036Y1733D01* -X1036Y1729D01* -X1038Y1729D01* -X1038Y1727D01* -X1040Y1727D01* -X1040Y1725D01* -X1042Y1725D01* -X1042Y1721D01* -X1044Y1721D01* -X1044Y1717D01* -X1046Y1717D01* -X1046Y1709D01* -X1048Y1709D01* -X1048Y1689D01* -X1046Y1689D01* -X1046Y1681D01* -X1044Y1681D01* -X1044Y1677D01* -X1042Y1677D01* -X1042Y1673D01* -X1040Y1673D01* -X1040Y1671D01* -X1038Y1671D01* -X1038Y1669D01* -X1036Y1669D01* -X1036Y1665D01* -X1034Y1665D01* -X1034Y1663D01* -X1030Y1663D01* -X1030Y1661D01* -X1028Y1661D01* -X1028Y1659D01* -X1026Y1659D01* -X1026Y1639D01* -X1028Y1639D01* -X1028Y1637D01* -X1032Y1637D01* -X1032Y1635D01* -X1034Y1635D01* -X1034Y1633D01* -X1036Y1633D01* -X1036Y1629D01* -X1038Y1629D01* -X1038Y1627D01* -X1040Y1627D01* -X1040Y1625D01* -X1042Y1625D01* -X1042Y1621D01* -X1044Y1621D01* -X1044Y1617D01* -X1046Y1617D01* -X1046Y1609D01* -X1048Y1609D01* -X1048Y1589D01* -X1046Y1589D01* -X1046Y1581D01* -X1044Y1581D01* -X1044Y1577D01* -X1042Y1577D01* -X1042Y1573D01* -X1040Y1573D01* -X1040Y1571D01* -X1038Y1571D01* -X1038Y1569D01* -X1036Y1569D01* -X1036Y1565D01* -X1034Y1565D01* -X1034Y1563D01* -X1030Y1563D01* -X1030Y1561D01* -X1028Y1561D01* -X1028Y1559D01* -X1026Y1559D01* -X1026Y1557D01* -X1022Y1557D01* -X1022Y1555D01* -X1018Y1555D01* -X1018Y1553D01* -X1012Y1553D01* -X1012Y1551D01* -X1178Y1551D01* -X1178Y1655D01* -X1176Y1655D01* -X1176Y1657D01* -X1172Y1657D01* -X1172Y1659D01* -X1170Y1659D01* -X1170Y1661D01* -X1168Y1661D01* -X1168Y1663D01* -X1166Y1663D01* -X1166Y1665D01* -X1164Y1665D01* -X1164Y1667D01* -X1162Y1667D01* -X1162Y1669D01* -X1160Y1669D01* -X1160Y1671D01* -X1158Y1671D01* -X1158Y1675D01* -X1156Y1675D01* -X1156Y1679D01* -X1154Y1679D01* -X1154Y1683D01* -X1152Y1683D01* -X1152Y1691D01* -X1150Y1691D01* -X1150Y1707D01* -X1152Y1707D01* -X1152Y1715D01* -X1154Y1715D01* -X1154Y1719D01* -X1156Y1719D01* -X1156Y1723D01* -X1158Y1723D01* -X1158Y1727D01* -X1160Y1727D01* -X1160Y1729D01* -X1162Y1729D01* -X1162Y1731D01* -X1164Y1731D01* -X1164Y1733D01* -X1166Y1733D01* -X1166Y1735D01* -X1168Y1735D01* -X1168Y1737D01* -X1170Y1737D01* -X1170Y1739D01* -X1172Y1739D01* -X1172Y1759D01* -X1026Y1759D01* -G37* -D02* -G36* -X1526Y1759D02* -X1526Y1739D01* -X1528Y1739D01* -X1528Y1737D01* -X1532Y1737D01* -X1532Y1735D01* -X1534Y1735D01* -X1534Y1733D01* -X1536Y1733D01* -X1536Y1729D01* -X1538Y1729D01* -X1538Y1727D01* -X1540Y1727D01* -X1540Y1725D01* -X1542Y1725D01* -X1542Y1721D01* -X1544Y1721D01* -X1544Y1717D01* -X1546Y1717D01* -X1546Y1709D01* -X1548Y1709D01* -X1548Y1689D01* -X1546Y1689D01* -X1546Y1681D01* -X1544Y1681D01* -X1544Y1677D01* -X1542Y1677D01* -X1542Y1673D01* -X1540Y1673D01* -X1540Y1671D01* -X1538Y1671D01* -X1538Y1669D01* -X1536Y1669D01* -X1536Y1665D01* -X1534Y1665D01* -X1534Y1663D01* -X1530Y1663D01* -X1530Y1661D01* -X1528Y1661D01* -X1528Y1659D01* -X1526Y1659D01* -X1526Y1657D01* -X1522Y1657D01* -X1522Y1645D01* -X1744Y1645D01* -X1744Y1621D01* -X1808Y1621D01* -X1808Y1619D01* -X1812Y1619D01* -X1812Y1617D01* -X1814Y1617D01* -X1814Y1615D01* -X1816Y1615D01* -X1816Y1613D01* -X1818Y1613D01* -X1818Y1609D01* -X1820Y1609D01* -X1820Y155D01* -X2288Y155D01* -X2288Y157D01* -X2282Y157D01* -X2282Y159D01* -X2278Y159D01* -X2278Y161D01* -X2274Y161D01* -X2274Y163D01* -X2272Y163D01* -X2272Y165D01* -X2268Y165D01* -X2268Y167D01* -X2266Y167D01* -X2266Y171D01* -X2264Y171D01* -X2264Y173D01* -X2262Y173D01* -X2262Y175D01* -X2260Y175D01* -X2260Y179D01* -X2258Y179D01* -X2258Y185D01* -X2256Y185D01* -X2256Y191D01* -X2254Y191D01* -X2254Y207D01* -X2256Y207D01* -X2256Y213D01* -X2258Y213D01* -X2258Y219D01* -X2260Y219D01* -X2260Y223D01* -X2262Y223D01* -X2262Y225D01* -X2264Y225D01* -X2264Y227D01* -X2266Y227D01* -X2266Y231D01* -X2268Y231D01* -X2268Y233D01* -X2272Y233D01* -X2272Y235D01* -X2274Y235D01* -X2274Y237D01* -X2278Y237D01* -X2278Y239D01* -X2280Y239D01* -X2280Y259D01* -X2278Y259D01* -X2278Y261D01* -X2274Y261D01* -X2274Y263D01* -X2272Y263D01* -X2272Y265D01* -X2268Y265D01* -X2268Y267D01* -X2266Y267D01* -X2266Y271D01* -X2264Y271D01* -X2264Y273D01* -X2262Y273D01* -X2262Y275D01* -X2260Y275D01* -X2260Y279D01* -X2258Y279D01* -X2258Y285D01* -X2256Y285D01* -X2256Y291D01* -X2254Y291D01* -X2254Y307D01* -X2256Y307D01* -X2256Y313D01* -X2258Y313D01* -X2258Y319D01* -X2260Y319D01* -X2260Y323D01* -X2262Y323D01* -X2262Y325D01* -X2264Y325D01* -X2264Y327D01* -X2266Y327D01* -X2266Y331D01* -X2268Y331D01* -X2268Y333D01* -X2272Y333D01* -X2272Y335D01* -X2274Y335D01* -X2274Y337D01* -X2278Y337D01* -X2278Y339D01* -X2280Y339D01* -X2280Y359D01* -X2278Y359D01* -X2278Y361D01* -X2274Y361D01* -X2274Y363D01* -X2272Y363D01* -X2272Y365D01* -X2268Y365D01* -X2268Y367D01* -X2266Y367D01* -X2266Y371D01* -X2264Y371D01* -X2264Y373D01* -X2262Y373D01* -X2262Y375D01* -X2260Y375D01* -X2260Y379D01* -X2258Y379D01* -X2258Y385D01* -X2256Y385D01* -X2256Y391D01* -X2254Y391D01* -X2254Y407D01* -X2256Y407D01* -X2256Y413D01* -X2258Y413D01* -X2258Y419D01* -X2260Y419D01* -X2260Y423D01* -X2262Y423D01* -X2262Y425D01* -X2264Y425D01* -X2264Y427D01* -X2266Y427D01* -X2266Y431D01* -X2268Y431D01* -X2268Y433D01* -X2272Y433D01* -X2272Y435D01* -X2274Y435D01* -X2274Y437D01* -X2278Y437D01* -X2278Y439D01* -X2280Y439D01* -X2280Y459D01* -X2278Y459D01* -X2278Y461D01* -X2274Y461D01* -X2274Y463D01* -X2272Y463D01* -X2272Y465D01* -X2268Y465D01* -X2268Y467D01* -X2266Y467D01* -X2266Y471D01* -X2264Y471D01* -X2264Y473D01* -X2262Y473D01* -X2262Y475D01* -X2260Y475D01* -X2260Y479D01* -X2258Y479D01* -X2258Y485D01* -X2256Y485D01* -X2256Y491D01* -X2254Y491D01* -X2254Y507D01* -X2256Y507D01* -X2256Y513D01* -X2258Y513D01* -X2258Y519D01* -X2260Y519D01* -X2260Y523D01* -X2262Y523D01* -X2262Y525D01* -X2264Y525D01* -X2264Y527D01* -X2266Y527D01* -X2266Y531D01* -X2268Y531D01* -X2268Y533D01* -X2272Y533D01* -X2272Y535D01* -X2274Y535D01* -X2274Y537D01* -X2278Y537D01* -X2278Y539D01* -X2280Y539D01* -X2280Y559D01* -X2278Y559D01* -X2278Y561D01* -X2274Y561D01* -X2274Y563D01* -X2272Y563D01* -X2272Y565D01* -X2268Y565D01* -X2268Y567D01* -X2266Y567D01* -X2266Y571D01* -X2264Y571D01* -X2264Y573D01* -X2262Y573D01* -X2262Y575D01* -X2260Y575D01* -X2260Y579D01* -X2258Y579D01* -X2258Y585D01* -X2256Y585D01* -X2256Y591D01* -X2254Y591D01* -X2254Y607D01* -X2256Y607D01* -X2256Y613D01* -X2258Y613D01* -X2258Y619D01* -X2260Y619D01* -X2260Y623D01* -X2262Y623D01* -X2262Y625D01* -X2264Y625D01* -X2264Y627D01* -X2266Y627D01* -X2266Y631D01* -X2268Y631D01* -X2268Y633D01* -X2272Y633D01* -X2272Y635D01* -X2274Y635D01* -X2274Y637D01* -X2278Y637D01* -X2278Y639D01* -X2280Y639D01* -X2280Y659D01* -X2278Y659D01* -X2278Y661D01* -X2274Y661D01* -X2274Y663D01* -X2272Y663D01* -X2272Y665D01* -X2268Y665D01* -X2268Y667D01* -X2266Y667D01* -X2266Y671D01* -X2264Y671D01* -X2264Y673D01* -X2262Y673D01* -X2262Y675D01* -X2260Y675D01* -X2260Y679D01* -X2258Y679D01* -X2258Y685D01* -X2256Y685D01* -X2256Y691D01* -X2254Y691D01* -X2254Y707D01* -X2256Y707D01* -X2256Y713D01* -X2258Y713D01* -X2258Y719D01* -X2260Y719D01* -X2260Y723D01* -X2262Y723D01* -X2262Y725D01* -X2264Y725D01* -X2264Y727D01* -X2266Y727D01* -X2266Y731D01* -X2268Y731D01* -X2268Y733D01* -X2272Y733D01* -X2272Y735D01* -X2274Y735D01* -X2274Y737D01* -X2278Y737D01* -X2278Y739D01* -X2280Y739D01* -X2280Y759D01* -X2278Y759D01* -X2278Y761D01* -X2274Y761D01* -X2274Y763D01* -X2272Y763D01* -X2272Y765D01* -X2268Y765D01* -X2268Y767D01* -X2266Y767D01* -X2266Y771D01* -X2264Y771D01* -X2264Y773D01* -X2262Y773D01* -X2262Y775D01* -X2260Y775D01* -X2260Y779D01* -X2258Y779D01* -X2258Y785D01* -X2256Y785D01* -X2256Y791D01* -X2254Y791D01* -X2254Y807D01* -X2256Y807D01* -X2256Y813D01* -X2258Y813D01* -X2258Y819D01* -X2260Y819D01* -X2260Y823D01* -X2262Y823D01* -X2262Y825D01* -X2264Y825D01* -X2264Y827D01* -X2266Y827D01* -X2266Y831D01* -X2268Y831D01* -X2268Y833D01* -X2272Y833D01* -X2272Y835D01* -X2274Y835D01* -X2274Y837D01* -X2278Y837D01* -X2278Y839D01* -X2280Y839D01* -X2280Y859D01* -X2278Y859D01* -X2278Y861D01* -X2274Y861D01* -X2274Y863D01* -X2272Y863D01* -X2272Y865D01* -X2268Y865D01* -X2268Y867D01* -X2266Y867D01* -X2266Y871D01* -X2264Y871D01* -X2264Y873D01* -X2262Y873D01* -X2262Y875D01* -X2260Y875D01* -X2260Y879D01* -X2258Y879D01* -X2258Y885D01* -X2256Y885D01* -X2256Y891D01* -X2254Y891D01* -X2254Y907D01* -X2256Y907D01* -X2256Y913D01* -X2258Y913D01* -X2258Y919D01* -X2260Y919D01* -X2260Y923D01* -X2262Y923D01* -X2262Y925D01* -X2264Y925D01* -X2264Y927D01* -X2266Y927D01* -X2266Y931D01* -X2268Y931D01* -X2268Y933D01* -X2272Y933D01* -X2272Y935D01* -X2274Y935D01* -X2274Y937D01* -X2278Y937D01* -X2278Y939D01* -X2280Y939D01* -X2280Y959D01* -X2278Y959D01* -X2278Y961D01* -X2274Y961D01* -X2274Y963D01* -X2272Y963D01* -X2272Y965D01* -X2268Y965D01* -X2268Y967D01* -X2266Y967D01* -X2266Y971D01* -X2264Y971D01* -X2264Y973D01* -X2262Y973D01* -X2262Y975D01* -X2260Y975D01* -X2260Y979D01* -X2258Y979D01* -X2258Y985D01* -X2256Y985D01* -X2256Y991D01* -X2254Y991D01* -X2254Y1007D01* -X2256Y1007D01* -X2256Y1013D01* -X2258Y1013D01* -X2258Y1019D01* -X2260Y1019D01* -X2260Y1023D01* -X2262Y1023D01* -X2262Y1025D01* -X2264Y1025D01* -X2264Y1027D01* -X2266Y1027D01* -X2266Y1031D01* -X2268Y1031D01* -X2268Y1033D01* -X2272Y1033D01* -X2272Y1035D01* -X2274Y1035D01* -X2274Y1037D01* -X2278Y1037D01* -X2278Y1039D01* -X2280Y1039D01* -X2280Y1059D01* -X2278Y1059D01* -X2278Y1061D01* -X2274Y1061D01* -X2274Y1063D01* -X2272Y1063D01* -X2272Y1065D01* -X2268Y1065D01* -X2268Y1067D01* -X2266Y1067D01* -X2266Y1071D01* -X2264Y1071D01* -X2264Y1073D01* -X2262Y1073D01* -X2262Y1075D01* -X2260Y1075D01* -X2260Y1079D01* -X2258Y1079D01* -X2258Y1085D01* -X2256Y1085D01* -X2256Y1091D01* -X2254Y1091D01* -X2254Y1107D01* -X2256Y1107D01* -X2256Y1113D01* -X2258Y1113D01* -X2258Y1119D01* -X2260Y1119D01* -X2260Y1123D01* -X2262Y1123D01* -X2262Y1125D01* -X2264Y1125D01* -X2264Y1127D01* -X2266Y1127D01* -X2266Y1131D01* -X2268Y1131D01* -X2268Y1133D01* -X2272Y1133D01* -X2272Y1135D01* -X2274Y1135D01* -X2274Y1137D01* -X2278Y1137D01* -X2278Y1139D01* -X2280Y1139D01* -X2280Y1159D01* -X2278Y1159D01* -X2278Y1161D01* -X2274Y1161D01* -X2274Y1163D01* -X2272Y1163D01* -X2272Y1165D01* -X2268Y1165D01* -X2268Y1167D01* -X2266Y1167D01* -X2266Y1171D01* -X2264Y1171D01* -X2264Y1173D01* -X2262Y1173D01* -X2262Y1175D01* -X2260Y1175D01* -X2260Y1179D01* -X2258Y1179D01* -X2258Y1185D01* -X2256Y1185D01* -X2256Y1191D01* -X2254Y1191D01* -X2254Y1207D01* -X2256Y1207D01* -X2256Y1213D01* -X2258Y1213D01* -X2258Y1219D01* -X2260Y1219D01* -X2260Y1223D01* -X2262Y1223D01* -X2262Y1225D01* -X2264Y1225D01* -X2264Y1227D01* -X2266Y1227D01* -X2266Y1231D01* -X2268Y1231D01* -X2268Y1233D01* -X2272Y1233D01* -X2272Y1235D01* -X2274Y1235D01* -X2274Y1237D01* -X2278Y1237D01* -X2278Y1239D01* -X2280Y1239D01* -X2280Y1259D01* -X2278Y1259D01* -X2278Y1261D01* -X2274Y1261D01* -X2274Y1263D01* -X2272Y1263D01* -X2272Y1265D01* -X2268Y1265D01* -X2268Y1267D01* -X2266Y1267D01* -X2266Y1271D01* -X2264Y1271D01* -X2264Y1273D01* -X2262Y1273D01* -X2262Y1275D01* -X2260Y1275D01* -X2260Y1279D01* -X2258Y1279D01* -X2258Y1285D01* -X2256Y1285D01* -X2256Y1291D01* -X2254Y1291D01* -X2254Y1307D01* -X2256Y1307D01* -X2256Y1313D01* -X2258Y1313D01* -X2258Y1319D01* -X2260Y1319D01* -X2260Y1323D01* -X2262Y1323D01* -X2262Y1325D01* -X2264Y1325D01* -X2264Y1327D01* -X2266Y1327D01* -X2266Y1331D01* -X2268Y1331D01* -X2268Y1333D01* -X2272Y1333D01* -X2272Y1335D01* -X2274Y1335D01* -X2274Y1337D01* -X2278Y1337D01* -X2278Y1339D01* -X2280Y1339D01* -X2280Y1359D01* -X2278Y1359D01* -X2278Y1361D01* -X2274Y1361D01* -X2274Y1363D01* -X2272Y1363D01* -X2272Y1365D01* -X2268Y1365D01* -X2268Y1367D01* -X2266Y1367D01* -X2266Y1371D01* -X2264Y1371D01* -X2264Y1373D01* -X2262Y1373D01* -X2262Y1375D01* -X2260Y1375D01* -X2260Y1379D01* -X2258Y1379D01* -X2258Y1385D01* -X2256Y1385D01* -X2256Y1391D01* -X2254Y1391D01* -X2254Y1407D01* -X2256Y1407D01* -X2256Y1413D01* -X2258Y1413D01* -X2258Y1419D01* -X2260Y1419D01* -X2260Y1423D01* -X2262Y1423D01* -X2262Y1425D01* -X2264Y1425D01* -X2264Y1427D01* -X2266Y1427D01* -X2266Y1431D01* -X2268Y1431D01* -X2268Y1433D01* -X2272Y1433D01* -X2272Y1435D01* -X2274Y1435D01* -X2274Y1437D01* -X2278Y1437D01* -X2278Y1439D01* -X2280Y1439D01* -X2280Y1459D01* -X2278Y1459D01* -X2278Y1461D01* -X2274Y1461D01* -X2274Y1463D01* -X2272Y1463D01* -X2272Y1465D01* -X2268Y1465D01* -X2268Y1467D01* -X2266Y1467D01* -X2266Y1471D01* -X2264Y1471D01* -X2264Y1473D01* -X2262Y1473D01* -X2262Y1475D01* -X2260Y1475D01* -X2260Y1479D01* -X2258Y1479D01* -X2258Y1485D01* -X2256Y1485D01* -X2256Y1491D01* -X2254Y1491D01* -X2254Y1507D01* -X2256Y1507D01* -X2256Y1513D01* -X2258Y1513D01* -X2258Y1519D01* -X2260Y1519D01* -X2260Y1523D01* -X2262Y1523D01* -X2262Y1525D01* -X2264Y1525D01* -X2264Y1527D01* -X2266Y1527D01* -X2266Y1531D01* -X2268Y1531D01* -X2268Y1533D01* -X2272Y1533D01* -X2272Y1535D01* -X2274Y1535D01* -X2274Y1537D01* -X2278Y1537D01* -X2278Y1539D01* -X2280Y1539D01* -X2280Y1559D01* -X2278Y1559D01* -X2278Y1561D01* -X2274Y1561D01* -X2274Y1563D01* -X2272Y1563D01* -X2272Y1565D01* -X2268Y1565D01* -X2268Y1567D01* -X2266Y1567D01* -X2266Y1571D01* -X2264Y1571D01* -X2264Y1573D01* -X2262Y1573D01* -X2262Y1575D01* -X2260Y1575D01* -X2260Y1579D01* -X2258Y1579D01* -X2258Y1585D01* -X2256Y1585D01* -X2256Y1591D01* -X2254Y1591D01* -X2254Y1607D01* -X2256Y1607D01* -X2256Y1613D01* -X2258Y1613D01* -X2258Y1619D01* -X2260Y1619D01* -X2260Y1623D01* -X2262Y1623D01* -X2262Y1625D01* -X2264Y1625D01* -X2264Y1627D01* -X2266Y1627D01* -X2266Y1631D01* -X2268Y1631D01* -X2268Y1633D01* -X2272Y1633D01* -X2272Y1635D01* -X2274Y1635D01* -X2274Y1637D01* -X2278Y1637D01* -X2278Y1639D01* -X2280Y1639D01* -X2280Y1641D01* -X2286Y1641D01* -X2286Y1643D01* -X2298Y1643D01* -X2298Y1645D01* -X2494Y1645D01* -X2494Y1647D01* -X2484Y1647D01* -X2484Y1649D01* -X2478Y1649D01* -X2478Y1651D01* -X2476Y1651D01* -X2476Y1653D01* -X2472Y1653D01* -X2472Y1655D01* -X2468Y1655D01* -X2468Y1657D01* -X2466Y1657D01* -X2466Y1659D01* -X2464Y1659D01* -X2464Y1661D01* -X2462Y1661D01* -X2462Y1663D01* -X2460Y1663D01* -X2460Y1665D01* -X2458Y1665D01* -X2458Y1667D01* -X2456Y1667D01* -X2456Y1669D01* -X2454Y1669D01* -X2454Y1673D01* -X2452Y1673D01* -X2452Y1677D01* -X2450Y1677D01* -X2450Y1681D01* -X2448Y1681D01* -X2448Y1689D01* -X2446Y1689D01* -X2446Y1709D01* -X2448Y1709D01* -X2448Y1717D01* -X2450Y1717D01* -X2450Y1721D01* -X2452Y1721D01* -X2452Y1725D01* -X2454Y1725D01* -X2454Y1729D01* -X2456Y1729D01* -X2456Y1731D01* -X2458Y1731D01* -X2458Y1733D01* -X2460Y1733D01* -X2460Y1737D01* -X2464Y1737D01* -X2464Y1739D01* -X2466Y1739D01* -X2466Y1759D01* -X1526Y1759D01* -G37* -D02* -G36* -X2542Y1669D02* -X2542Y1667D01* -X2540Y1667D01* -X2540Y1663D01* -X2538Y1663D01* -X2538Y1661D01* -X2536Y1661D01* -X2536Y1659D01* -X2532Y1659D01* -X2532Y1657D01* -X2530Y1657D01* -X2530Y1655D01* -X2528Y1655D01* -X2528Y1653D01* -X2524Y1653D01* -X2524Y1651D01* -X2520Y1651D01* -X2520Y1649D01* -X2514Y1649D01* -X2514Y1647D01* -X2504Y1647D01* -X2504Y1645D01* -X2562Y1645D01* -X2562Y1669D01* -X2542Y1669D01* -G37* -D02* -G36* -X40Y1665D02* -X40Y1645D01* -X94Y1645D01* -X94Y1647D01* -X84Y1647D01* -X84Y1649D01* -X78Y1649D01* -X78Y1651D01* -X76Y1651D01* -X76Y1653D01* -X72Y1653D01* -X72Y1655D01* -X68Y1655D01* -X68Y1657D01* -X66Y1657D01* -X66Y1659D01* -X64Y1659D01* -X64Y1661D01* -X62Y1661D01* -X62Y1663D01* -X60Y1663D01* -X60Y1665D01* -X40Y1665D01* -G37* -D02* -G36* -X40Y1645D02* -X40Y1643D01* -X272Y1643D01* -X272Y1645D01* -X40Y1645D01* -G37* -D02* -G36* -X40Y1645D02* -X40Y1643D01* -X272Y1643D01* -X272Y1645D01* -X40Y1645D01* -G37* -D02* -G36* -X1522Y1645D02* -X1522Y1521D01* -X1660Y1521D01* -X1660Y1523D01* -X1662Y1523D01* -X1662Y1525D01* -X1664Y1525D01* -X1664Y1527D01* -X1666Y1527D01* -X1666Y1531D01* -X1668Y1531D01* -X1668Y1533D01* -X1672Y1533D01* -X1672Y1535D01* -X1674Y1535D01* -X1674Y1555D01* -X1654Y1555D01* -X1654Y1643D01* -X1656Y1643D01* -X1656Y1645D01* -X1522Y1645D01* -G37* -D02* -G36* -X2300Y1645D02* -X2300Y1643D01* -X2562Y1643D01* -X2562Y1645D01* -X2300Y1645D01* -G37* -D02* -G36* -X2300Y1645D02* -X2300Y1643D01* -X2562Y1643D01* -X2562Y1645D01* -X2300Y1645D01* -G37* -D02* -G36* -X40Y1643D02* -X40Y1551D01* -X286Y1551D01* -X286Y1553D01* -X280Y1553D01* -X280Y1555D01* -X276Y1555D01* -X276Y1557D01* -X272Y1557D01* -X272Y1559D01* -X270Y1559D01* -X270Y1561D01* -X268Y1561D01* -X268Y1563D01* -X266Y1563D01* -X266Y1565D01* -X264Y1565D01* -X264Y1567D01* -X262Y1567D01* -X262Y1569D01* -X260Y1569D01* -X260Y1571D01* -X258Y1571D01* -X258Y1575D01* -X256Y1575D01* -X256Y1579D01* -X254Y1579D01* -X254Y1583D01* -X252Y1583D01* -X252Y1591D01* -X250Y1591D01* -X250Y1607D01* -X252Y1607D01* -X252Y1615D01* -X254Y1615D01* -X254Y1619D01* -X256Y1619D01* -X256Y1623D01* -X258Y1623D01* -X258Y1627D01* -X260Y1627D01* -X260Y1629D01* -X262Y1629D01* -X262Y1631D01* -X264Y1631D01* -X264Y1633D01* -X266Y1633D01* -X266Y1635D01* -X268Y1635D01* -X268Y1637D01* -X270Y1637D01* -X270Y1639D01* -X272Y1639D01* -X272Y1643D01* -X40Y1643D01* -G37* -D02* -G36* -X2312Y1643D02* -X2312Y1641D01* -X2318Y1641D01* -X2318Y1639D01* -X2322Y1639D01* -X2322Y1637D01* -X2324Y1637D01* -X2324Y1635D01* -X2328Y1635D01* -X2328Y1633D01* -X2330Y1633D01* -X2330Y1631D01* -X2332Y1631D01* -X2332Y1629D01* -X2334Y1629D01* -X2334Y1627D01* -X2336Y1627D01* -X2336Y1623D01* -X2338Y1623D01* -X2338Y1619D01* -X2340Y1619D01* -X2340Y1615D01* -X2342Y1615D01* -X2342Y1609D01* -X2344Y1609D01* -X2344Y1589D01* -X2342Y1589D01* -X2342Y1583D01* -X2340Y1583D01* -X2340Y1579D01* -X2338Y1579D01* -X2338Y1575D01* -X2336Y1575D01* -X2336Y1573D01* -X2334Y1573D01* -X2334Y1569D01* -X2332Y1569D01* -X2332Y1567D01* -X2330Y1567D01* -X2330Y1565D01* -X2328Y1565D01* -X2328Y1563D01* -X2324Y1563D01* -X2324Y1561D01* -X2322Y1561D01* -X2322Y1559D01* -X2318Y1559D01* -X2318Y1539D01* -X2322Y1539D01* -X2322Y1537D01* -X2324Y1537D01* -X2324Y1535D01* -X2328Y1535D01* -X2328Y1533D01* -X2330Y1533D01* -X2330Y1531D01* -X2332Y1531D01* -X2332Y1529D01* -X2334Y1529D01* -X2334Y1527D01* -X2336Y1527D01* -X2336Y1523D01* -X2338Y1523D01* -X2338Y1519D01* -X2340Y1519D01* -X2340Y1515D01* -X2342Y1515D01* -X2342Y1509D01* -X2344Y1509D01* -X2344Y1489D01* -X2342Y1489D01* -X2342Y1483D01* -X2340Y1483D01* -X2340Y1479D01* -X2338Y1479D01* -X2338Y1475D01* -X2336Y1475D01* -X2336Y1473D01* -X2334Y1473D01* -X2334Y1469D01* -X2332Y1469D01* -X2332Y1467D01* -X2330Y1467D01* -X2330Y1465D01* -X2328Y1465D01* -X2328Y1463D01* -X2324Y1463D01* -X2324Y1461D01* -X2322Y1461D01* -X2322Y1459D01* -X2318Y1459D01* -X2318Y1439D01* -X2322Y1439D01* -X2322Y1437D01* -X2324Y1437D01* -X2324Y1435D01* -X2328Y1435D01* -X2328Y1433D01* -X2330Y1433D01* -X2330Y1431D01* -X2332Y1431D01* -X2332Y1429D01* -X2334Y1429D01* -X2334Y1427D01* -X2336Y1427D01* -X2336Y1423D01* -X2338Y1423D01* -X2338Y1419D01* -X2340Y1419D01* -X2340Y1415D01* -X2342Y1415D01* -X2342Y1409D01* -X2344Y1409D01* -X2344Y1389D01* -X2342Y1389D01* -X2342Y1383D01* -X2340Y1383D01* -X2340Y1379D01* -X2338Y1379D01* -X2338Y1375D01* -X2336Y1375D01* -X2336Y1373D01* -X2334Y1373D01* -X2334Y1369D01* -X2332Y1369D01* -X2332Y1367D01* -X2330Y1367D01* -X2330Y1365D01* -X2328Y1365D01* -X2328Y1363D01* -X2324Y1363D01* -X2324Y1361D01* -X2322Y1361D01* -X2322Y1359D01* -X2318Y1359D01* -X2318Y1339D01* -X2322Y1339D01* -X2322Y1337D01* -X2324Y1337D01* -X2324Y1335D01* -X2328Y1335D01* -X2328Y1333D01* -X2330Y1333D01* -X2330Y1331D01* -X2332Y1331D01* -X2332Y1329D01* -X2334Y1329D01* -X2334Y1327D01* -X2336Y1327D01* -X2336Y1323D01* -X2338Y1323D01* -X2338Y1319D01* -X2340Y1319D01* -X2340Y1315D01* -X2342Y1315D01* -X2342Y1309D01* -X2344Y1309D01* -X2344Y1289D01* -X2342Y1289D01* -X2342Y1283D01* -X2340Y1283D01* -X2340Y1279D01* -X2338Y1279D01* -X2338Y1275D01* -X2336Y1275D01* -X2336Y1273D01* -X2334Y1273D01* -X2334Y1269D01* -X2332Y1269D01* -X2332Y1267D01* -X2330Y1267D01* -X2330Y1265D01* -X2328Y1265D01* -X2328Y1263D01* -X2324Y1263D01* -X2324Y1261D01* -X2322Y1261D01* -X2322Y1259D01* -X2318Y1259D01* -X2318Y1239D01* -X2322Y1239D01* -X2322Y1237D01* -X2324Y1237D01* -X2324Y1235D01* -X2328Y1235D01* -X2328Y1233D01* -X2330Y1233D01* -X2330Y1231D01* -X2332Y1231D01* -X2332Y1229D01* -X2334Y1229D01* -X2334Y1227D01* -X2336Y1227D01* -X2336Y1223D01* -X2338Y1223D01* -X2338Y1219D01* -X2340Y1219D01* -X2340Y1215D01* -X2342Y1215D01* -X2342Y1209D01* -X2344Y1209D01* -X2344Y1189D01* -X2342Y1189D01* -X2342Y1183D01* -X2340Y1183D01* -X2340Y1179D01* -X2338Y1179D01* -X2338Y1175D01* -X2336Y1175D01* -X2336Y1173D01* -X2334Y1173D01* -X2334Y1169D01* -X2332Y1169D01* -X2332Y1167D01* -X2330Y1167D01* -X2330Y1165D01* -X2328Y1165D01* -X2328Y1163D01* -X2324Y1163D01* -X2324Y1161D01* -X2322Y1161D01* -X2322Y1159D01* -X2318Y1159D01* -X2318Y1139D01* -X2322Y1139D01* -X2322Y1137D01* -X2324Y1137D01* -X2324Y1135D01* -X2328Y1135D01* -X2328Y1133D01* -X2330Y1133D01* -X2330Y1131D01* -X2332Y1131D01* -X2332Y1129D01* -X2334Y1129D01* -X2334Y1127D01* -X2336Y1127D01* -X2336Y1123D01* -X2338Y1123D01* -X2338Y1119D01* -X2340Y1119D01* -X2340Y1115D01* -X2342Y1115D01* -X2342Y1109D01* -X2344Y1109D01* -X2344Y1089D01* -X2342Y1089D01* -X2342Y1083D01* -X2340Y1083D01* -X2340Y1079D01* -X2338Y1079D01* -X2338Y1075D01* -X2336Y1075D01* -X2336Y1073D01* -X2334Y1073D01* -X2334Y1069D01* -X2332Y1069D01* -X2332Y1067D01* -X2330Y1067D01* -X2330Y1065D01* -X2328Y1065D01* -X2328Y1063D01* -X2324Y1063D01* -X2324Y1061D01* -X2322Y1061D01* -X2322Y1059D01* -X2318Y1059D01* -X2318Y1039D01* -X2322Y1039D01* -X2322Y1037D01* -X2324Y1037D01* -X2324Y1035D01* -X2328Y1035D01* -X2328Y1033D01* -X2330Y1033D01* -X2330Y1031D01* -X2332Y1031D01* -X2332Y1029D01* -X2334Y1029D01* -X2334Y1027D01* -X2336Y1027D01* -X2336Y1023D01* -X2338Y1023D01* -X2338Y1019D01* -X2340Y1019D01* -X2340Y1015D01* -X2342Y1015D01* -X2342Y1009D01* -X2344Y1009D01* -X2344Y989D01* -X2342Y989D01* -X2342Y983D01* -X2340Y983D01* -X2340Y979D01* -X2338Y979D01* -X2338Y975D01* -X2336Y975D01* -X2336Y973D01* -X2334Y973D01* -X2334Y969D01* -X2332Y969D01* -X2332Y967D01* -X2330Y967D01* -X2330Y965D01* -X2328Y965D01* -X2328Y963D01* -X2324Y963D01* -X2324Y961D01* -X2322Y961D01* -X2322Y959D01* -X2318Y959D01* -X2318Y939D01* -X2322Y939D01* -X2322Y937D01* -X2324Y937D01* -X2324Y935D01* -X2328Y935D01* -X2328Y933D01* -X2330Y933D01* -X2330Y931D01* -X2332Y931D01* -X2332Y929D01* -X2334Y929D01* -X2334Y927D01* -X2336Y927D01* -X2336Y923D01* -X2338Y923D01* -X2338Y919D01* -X2340Y919D01* -X2340Y915D01* -X2342Y915D01* -X2342Y909D01* -X2344Y909D01* -X2344Y889D01* -X2342Y889D01* -X2342Y883D01* -X2340Y883D01* -X2340Y879D01* -X2338Y879D01* -X2338Y875D01* -X2336Y875D01* -X2336Y873D01* -X2334Y873D01* -X2334Y869D01* -X2332Y869D01* -X2332Y867D01* -X2330Y867D01* -X2330Y865D01* -X2328Y865D01* -X2328Y863D01* -X2324Y863D01* -X2324Y861D01* -X2322Y861D01* -X2322Y859D01* -X2318Y859D01* -X2318Y839D01* -X2322Y839D01* -X2322Y837D01* -X2324Y837D01* -X2324Y835D01* -X2328Y835D01* -X2328Y833D01* -X2330Y833D01* -X2330Y831D01* -X2332Y831D01* -X2332Y829D01* -X2334Y829D01* -X2334Y827D01* -X2336Y827D01* -X2336Y823D01* -X2338Y823D01* -X2338Y819D01* -X2340Y819D01* -X2340Y815D01* -X2342Y815D01* -X2342Y809D01* -X2344Y809D01* -X2344Y789D01* -X2342Y789D01* -X2342Y783D01* -X2340Y783D01* -X2340Y779D01* -X2338Y779D01* -X2338Y775D01* -X2336Y775D01* -X2336Y773D01* -X2334Y773D01* -X2334Y769D01* -X2332Y769D01* -X2332Y767D01* -X2330Y767D01* -X2330Y765D01* -X2328Y765D01* -X2328Y763D01* -X2324Y763D01* -X2324Y761D01* -X2322Y761D01* -X2322Y759D01* -X2318Y759D01* -X2318Y739D01* -X2322Y739D01* -X2322Y737D01* -X2324Y737D01* -X2324Y735D01* -X2328Y735D01* -X2328Y733D01* -X2330Y733D01* -X2330Y731D01* -X2332Y731D01* -X2332Y729D01* -X2334Y729D01* -X2334Y727D01* -X2336Y727D01* -X2336Y723D01* -X2338Y723D01* -X2338Y719D01* -X2340Y719D01* -X2340Y715D01* -X2342Y715D01* -X2342Y709D01* -X2344Y709D01* -X2344Y689D01* -X2342Y689D01* -X2342Y683D01* -X2340Y683D01* -X2340Y679D01* -X2338Y679D01* -X2338Y675D01* -X2336Y675D01* -X2336Y673D01* -X2334Y673D01* -X2334Y669D01* -X2332Y669D01* -X2332Y667D01* -X2330Y667D01* -X2330Y665D01* -X2328Y665D01* -X2328Y663D01* -X2324Y663D01* -X2324Y661D01* -X2322Y661D01* -X2322Y659D01* -X2318Y659D01* -X2318Y639D01* -X2322Y639D01* -X2322Y637D01* -X2324Y637D01* -X2324Y635D01* -X2328Y635D01* -X2328Y633D01* -X2330Y633D01* -X2330Y631D01* -X2332Y631D01* -X2332Y629D01* -X2334Y629D01* -X2334Y627D01* -X2336Y627D01* -X2336Y623D01* -X2338Y623D01* -X2338Y619D01* -X2340Y619D01* -X2340Y615D01* -X2342Y615D01* -X2342Y609D01* -X2344Y609D01* -X2344Y589D01* -X2342Y589D01* -X2342Y583D01* -X2340Y583D01* -X2340Y579D01* -X2338Y579D01* -X2338Y575D01* -X2336Y575D01* -X2336Y573D01* -X2334Y573D01* -X2334Y569D01* -X2332Y569D01* -X2332Y567D01* -X2330Y567D01* -X2330Y565D01* -X2328Y565D01* -X2328Y563D01* -X2324Y563D01* -X2324Y561D01* -X2322Y561D01* -X2322Y559D01* -X2318Y559D01* -X2318Y539D01* -X2322Y539D01* -X2322Y537D01* -X2324Y537D01* -X2324Y535D01* -X2328Y535D01* -X2328Y533D01* -X2330Y533D01* -X2330Y531D01* -X2332Y531D01* -X2332Y529D01* -X2334Y529D01* -X2334Y527D01* -X2336Y527D01* -X2336Y523D01* -X2338Y523D01* -X2338Y519D01* -X2340Y519D01* -X2340Y515D01* -X2342Y515D01* -X2342Y509D01* -X2344Y509D01* -X2344Y489D01* -X2342Y489D01* -X2342Y483D01* -X2340Y483D01* -X2340Y479D01* -X2338Y479D01* -X2338Y475D01* -X2336Y475D01* -X2336Y473D01* -X2334Y473D01* -X2334Y469D01* -X2332Y469D01* -X2332Y467D01* -X2330Y467D01* -X2330Y465D01* -X2328Y465D01* -X2328Y463D01* -X2324Y463D01* -X2324Y461D01* -X2322Y461D01* -X2322Y459D01* -X2318Y459D01* -X2318Y439D01* -X2322Y439D01* -X2322Y437D01* -X2324Y437D01* -X2324Y435D01* -X2328Y435D01* -X2328Y433D01* -X2330Y433D01* -X2330Y431D01* -X2332Y431D01* -X2332Y429D01* -X2334Y429D01* -X2334Y427D01* -X2336Y427D01* -X2336Y423D01* -X2338Y423D01* -X2338Y419D01* -X2340Y419D01* -X2340Y415D01* -X2342Y415D01* -X2342Y409D01* -X2344Y409D01* -X2344Y389D01* -X2342Y389D01* -X2342Y383D01* -X2340Y383D01* -X2340Y379D01* -X2338Y379D01* -X2338Y375D01* -X2336Y375D01* -X2336Y373D01* -X2334Y373D01* -X2334Y369D01* -X2332Y369D01* -X2332Y367D01* -X2330Y367D01* -X2330Y365D01* -X2328Y365D01* -X2328Y363D01* -X2324Y363D01* -X2324Y361D01* -X2322Y361D01* -X2322Y359D01* -X2318Y359D01* -X2318Y339D01* -X2322Y339D01* -X2322Y337D01* -X2324Y337D01* -X2324Y335D01* -X2328Y335D01* -X2328Y333D01* -X2330Y333D01* -X2330Y331D01* -X2332Y331D01* -X2332Y329D01* -X2334Y329D01* -X2334Y327D01* -X2336Y327D01* -X2336Y323D01* -X2338Y323D01* -X2338Y319D01* -X2340Y319D01* -X2340Y315D01* -X2342Y315D01* -X2342Y309D01* -X2344Y309D01* -X2344Y289D01* -X2342Y289D01* -X2342Y283D01* -X2340Y283D01* -X2340Y279D01* -X2338Y279D01* -X2338Y275D01* -X2336Y275D01* -X2336Y273D01* -X2334Y273D01* -X2334Y269D01* -X2332Y269D01* -X2332Y267D01* -X2330Y267D01* -X2330Y265D01* -X2328Y265D01* -X2328Y263D01* -X2324Y263D01* -X2324Y261D01* -X2322Y261D01* -X2322Y259D01* -X2318Y259D01* -X2318Y239D01* -X2322Y239D01* -X2322Y237D01* -X2324Y237D01* -X2324Y235D01* -X2328Y235D01* -X2328Y233D01* -X2330Y233D01* -X2330Y231D01* -X2332Y231D01* -X2332Y229D01* -X2334Y229D01* -X2334Y227D01* -X2336Y227D01* -X2336Y223D01* -X2338Y223D01* -X2338Y219D01* -X2340Y219D01* -X2340Y215D01* -X2342Y215D01* -X2342Y209D01* -X2344Y209D01* -X2344Y189D01* -X2342Y189D01* -X2342Y183D01* -X2340Y183D01* -X2340Y179D01* -X2338Y179D01* -X2338Y175D01* -X2336Y175D01* -X2336Y173D01* -X2334Y173D01* -X2334Y169D01* -X2332Y169D01* -X2332Y167D01* -X2330Y167D01* -X2330Y165D01* -X2328Y165D01* -X2328Y163D01* -X2324Y163D01* -X2324Y161D01* -X2322Y161D01* -X2322Y159D01* -X2318Y159D01* -X2318Y157D01* -X2312Y157D01* -X2312Y155D01* -X2562Y155D01* -X2562Y1643D01* -X2312Y1643D01* -G37* -D02* -G36* -X40Y1551D02* -X40Y1549D01* -X1178Y1549D01* -X1178Y1551D01* -X40Y1551D01* -G37* -D02* -G36* -X40Y1551D02* -X40Y1549D01* -X1178Y1549D01* -X1178Y1551D01* -X40Y1551D01* -G37* -D02* -G36* -X40Y1551D02* -X40Y1549D01* -X1178Y1549D01* -X1178Y1551D01* -X40Y1551D01* -G37* -D02* -G36* -X40Y1549D02* -X40Y153D01* -X104Y153D01* -X104Y151D01* -X114Y151D01* -X114Y149D01* -X1500Y149D01* -X1500Y147D01* -X1512Y147D01* -X1512Y145D01* -X1518Y145D01* -X1518Y143D01* -X1522Y143D01* -X1522Y141D01* -X1526Y141D01* -X1526Y139D01* -X1528Y139D01* -X1528Y137D01* -X1532Y137D01* -X1532Y135D01* -X1534Y135D01* -X1534Y133D01* -X1536Y133D01* -X1536Y129D01* -X1538Y129D01* -X1538Y127D01* -X1540Y127D01* -X1540Y125D01* -X1542Y125D01* -X1542Y121D01* -X1544Y121D01* -X1544Y117D01* -X1546Y117D01* -X1546Y109D01* -X1548Y109D01* -X1548Y89D01* -X1546Y89D01* -X1546Y81D01* -X1544Y81D01* -X1544Y77D01* -X1596Y77D01* -X1596Y79D01* -X1590Y79D01* -X1590Y81D01* -X1588Y81D01* -X1588Y83D01* -X1584Y83D01* -X1584Y87D01* -X1582Y87D01* -X1582Y89D01* -X1580Y89D01* -X1580Y93D01* -X1578Y93D01* -X1578Y377D01* -X192Y377D01* -X192Y379D01* -X188Y379D01* -X188Y381D01* -X184Y381D01* -X184Y383D01* -X182Y383D01* -X182Y385D01* -X180Y385D01* -X180Y389D01* -X178Y389D01* -X178Y393D01* -X176Y393D01* -X176Y1203D01* -X178Y1203D01* -X178Y1209D01* -X180Y1209D01* -X180Y1211D01* -X182Y1211D01* -X182Y1213D01* -X184Y1213D01* -X184Y1215D01* -X186Y1215D01* -X186Y1217D01* -X190Y1217D01* -X190Y1219D01* -X198Y1219D01* -X198Y1221D01* -X1176Y1221D01* -X1176Y1537D01* -X1178Y1537D01* -X1178Y1549D01* -X40Y1549D01* -G37* -D02* -G36* -X1820Y155D02* -X1820Y153D01* -X2562Y153D01* -X2562Y155D01* -X1820Y155D01* -G37* -D02* -G36* -X1820Y155D02* -X1820Y153D01* -X2562Y153D01* -X2562Y155D01* -X1820Y155D01* -G37* -D02* -G36* -X40Y153D02* -X40Y133D01* -X60Y133D01* -X60Y137D01* -X64Y137D01* -X64Y139D01* -X66Y139D01* -X66Y141D01* -X68Y141D01* -X68Y143D01* -X72Y143D01* -X72Y145D01* -X74Y145D01* -X74Y147D01* -X78Y147D01* -X78Y149D01* -X84Y149D01* -X84Y151D01* -X94Y151D01* -X94Y153D01* -X40Y153D01* -G37* -D02* -G36* -X1820Y153D02* -X1820Y91D01* -X1818Y91D01* -X1818Y87D01* -X1816Y87D01* -X1816Y85D01* -X1814Y85D01* -X1814Y83D01* -X1812Y83D01* -X1812Y81D01* -X1808Y81D01* -X1808Y79D01* -X1802Y79D01* -X1802Y77D01* -X2450Y77D01* -X2450Y81D01* -X2448Y81D01* -X2448Y89D01* -X2446Y89D01* -X2446Y109D01* -X2448Y109D01* -X2448Y117D01* -X2450Y117D01* -X2450Y121D01* -X2452Y121D01* -X2452Y125D01* -X2454Y125D01* -X2454Y129D01* -X2456Y129D01* -X2456Y131D01* -X2458Y131D01* -X2458Y133D01* -X2460Y133D01* -X2460Y137D01* -X2464Y137D01* -X2464Y139D01* -X2466Y139D01* -X2466Y141D01* -X2468Y141D01* -X2468Y143D01* -X2472Y143D01* -X2472Y145D01* -X2474Y145D01* -X2474Y147D01* -X2478Y147D01* -X2478Y149D01* -X2484Y149D01* -X2484Y151D01* -X2494Y151D01* -X2494Y153D01* -X1820Y153D01* -G37* -D02* -G36* -X2504Y153D02* -X2504Y151D01* -X2514Y151D01* -X2514Y149D01* -X2520Y149D01* -X2520Y147D01* -X2524Y147D01* -X2524Y145D01* -X2528Y145D01* -X2528Y143D01* -X2530Y143D01* -X2530Y141D01* -X2532Y141D01* -X2532Y139D01* -X2536Y139D01* -X2536Y137D01* -X2538Y137D01* -X2538Y135D01* -X2540Y135D01* -X2540Y131D01* -X2542Y131D01* -X2542Y129D01* -X2562Y129D01* -X2562Y153D01* -X2504Y153D01* -G37* -D02* -G36* -X120Y149D02* -X120Y147D01* -X124Y147D01* -X124Y145D01* -X128Y145D01* -X128Y143D01* -X130Y143D01* -X130Y141D01* -X132Y141D01* -X132Y139D01* -X136Y139D01* -X136Y137D01* -X138Y137D01* -X138Y135D01* -X140Y135D01* -X140Y131D01* -X142Y131D01* -X142Y129D01* -X144Y129D01* -X144Y125D01* -X146Y125D01* -X146Y123D01* -X148Y123D01* -X148Y117D01* -X150Y117D01* -X150Y111D01* -X152Y111D01* -X152Y87D01* -X150Y87D01* -X150Y81D01* -X148Y81D01* -X148Y77D01* -X146Y77D01* -X146Y73D01* -X144Y73D01* -X144Y69D01* -X142Y69D01* -X142Y67D01* -X140Y67D01* -X140Y63D01* -X138Y63D01* -X138Y61D01* -X136Y61D01* -X136Y41D01* -X1170Y41D01* -X1170Y61D01* -X1168Y61D01* -X1168Y63D01* -X1166Y63D01* -X1166Y65D01* -X1164Y65D01* -X1164Y67D01* -X1162Y67D01* -X1162Y69D01* -X1160Y69D01* -X1160Y71D01* -X1158Y71D01* -X1158Y75D01* -X1156Y75D01* -X1156Y79D01* -X1154Y79D01* -X1154Y83D01* -X1152Y83D01* -X1152Y91D01* -X1150Y91D01* -X1150Y107D01* -X1152Y107D01* -X1152Y115D01* -X1154Y115D01* -X1154Y119D01* -X1156Y119D01* -X1156Y123D01* -X1158Y123D01* -X1158Y127D01* -X1160Y127D01* -X1160Y129D01* -X1162Y129D01* -X1162Y131D01* -X1164Y131D01* -X1164Y133D01* -X1166Y133D01* -X1166Y135D01* -X1168Y135D01* -X1168Y137D01* -X1170Y137D01* -X1170Y139D01* -X1172Y139D01* -X1172Y141D01* -X1176Y141D01* -X1176Y143D01* -X1180Y143D01* -X1180Y145D01* -X1186Y145D01* -X1186Y147D01* -X1198Y147D01* -X1198Y149D01* -X120Y149D01* -G37* -D02* -G36* -X1200Y149D02* -X1200Y147D01* -X1212Y147D01* -X1212Y145D01* -X1218Y145D01* -X1218Y143D01* -X1222Y143D01* -X1222Y141D01* -X1226Y141D01* -X1226Y139D01* -X1228Y139D01* -X1228Y137D01* -X1232Y137D01* -X1232Y135D01* -X1234Y135D01* -X1234Y133D01* -X1236Y133D01* -X1236Y129D01* -X1238Y129D01* -X1238Y127D01* -X1260Y127D01* -X1260Y129D01* -X1262Y129D01* -X1262Y131D01* -X1264Y131D01* -X1264Y133D01* -X1266Y133D01* -X1266Y135D01* -X1268Y135D01* -X1268Y137D01* -X1270Y137D01* -X1270Y139D01* -X1272Y139D01* -X1272Y141D01* -X1276Y141D01* -X1276Y143D01* -X1280Y143D01* -X1280Y145D01* -X1286Y145D01* -X1286Y147D01* -X1298Y147D01* -X1298Y149D01* -X1200Y149D01* -G37* -D02* -G36* -X1300Y149D02* -X1300Y147D01* -X1312Y147D01* -X1312Y145D01* -X1318Y145D01* -X1318Y143D01* -X1322Y143D01* -X1322Y141D01* -X1326Y141D01* -X1326Y139D01* -X1328Y139D01* -X1328Y137D01* -X1332Y137D01* -X1332Y135D01* -X1334Y135D01* -X1334Y133D01* -X1336Y133D01* -X1336Y129D01* -X1338Y129D01* -X1338Y127D01* -X1360Y127D01* -X1360Y129D01* -X1362Y129D01* -X1362Y131D01* -X1364Y131D01* -X1364Y133D01* -X1366Y133D01* -X1366Y135D01* -X1368Y135D01* -X1368Y137D01* -X1370Y137D01* -X1370Y139D01* -X1372Y139D01* -X1372Y141D01* -X1376Y141D01* -X1376Y143D01* -X1380Y143D01* -X1380Y145D01* -X1386Y145D01* -X1386Y147D01* -X1398Y147D01* -X1398Y149D01* -X1300Y149D01* -G37* -D02* -G36* -X1400Y149D02* -X1400Y147D01* -X1412Y147D01* -X1412Y145D01* -X1418Y145D01* -X1418Y143D01* -X1422Y143D01* -X1422Y141D01* -X1426Y141D01* -X1426Y139D01* -X1428Y139D01* -X1428Y137D01* -X1432Y137D01* -X1432Y135D01* -X1434Y135D01* -X1434Y133D01* -X1436Y133D01* -X1436Y129D01* -X1438Y129D01* -X1438Y127D01* -X1460Y127D01* -X1460Y129D01* -X1462Y129D01* -X1462Y131D01* -X1464Y131D01* -X1464Y133D01* -X1466Y133D01* -X1466Y135D01* -X1468Y135D01* -X1468Y137D01* -X1470Y137D01* -X1470Y139D01* -X1472Y139D01* -X1472Y141D01* -X1476Y141D01* -X1476Y143D01* -X1480Y143D01* -X1480Y145D01* -X1486Y145D01* -X1486Y147D01* -X1498Y147D01* -X1498Y149D01* -X1400Y149D01* -G37* -D02* -G36* -X1542Y77D02* -X1542Y75D01* -X2452Y75D01* -X2452Y77D01* -X1542Y77D01* -G37* -D02* -G36* -X1542Y77D02* -X1542Y75D01* -X2452Y75D01* -X2452Y77D01* -X1542Y77D01* -G37* -D02* -G36* -X1542Y75D02* -X1542Y73D01* -X1540Y73D01* -X1540Y71D01* -X1538Y71D01* -X1538Y69D01* -X1536Y69D01* -X1536Y65D01* -X1534Y65D01* -X1534Y63D01* -X1530Y63D01* -X1530Y61D01* -X1528Y61D01* -X1528Y41D01* -X2464Y41D01* -X2464Y61D01* -X2462Y61D01* -X2462Y63D01* -X2460Y63D01* -X2460Y65D01* -X2458Y65D01* -X2458Y67D01* -X2456Y67D01* -X2456Y69D01* -X2454Y69D01* -X2454Y73D01* -X2452Y73D01* -X2452Y75D01* -X1542Y75D01* -G37* -D02* -G36* -X638Y1071D02* -X638Y1069D01* -X636Y1069D01* -X636Y1065D01* -X634Y1065D01* -X634Y1063D01* -X630Y1063D01* -X630Y1061D01* -X628Y1061D01* -X628Y1059D01* -X626Y1059D01* -X626Y1057D01* -X622Y1057D01* -X622Y1051D01* -X686Y1051D01* -X686Y1053D01* -X680Y1053D01* -X680Y1055D01* -X676Y1055D01* -X676Y1057D01* -X672Y1057D01* -X672Y1059D01* -X670Y1059D01* -X670Y1061D01* -X668Y1061D01* -X668Y1063D01* -X666Y1063D01* -X666Y1065D01* -X664Y1065D01* -X664Y1067D01* -X662Y1067D01* -X662Y1069D01* -X660Y1069D01* -X660Y1071D01* -X638Y1071D01* -G37* -D02* -G36* -X738Y1071D02* -X738Y1069D01* -X736Y1069D01* -X736Y1065D01* -X734Y1065D01* -X734Y1063D01* -X730Y1063D01* -X730Y1061D01* -X728Y1061D01* -X728Y1059D01* -X726Y1059D01* -X726Y1057D01* -X722Y1057D01* -X722Y1055D01* -X718Y1055D01* -X718Y1053D01* -X712Y1053D01* -X712Y1051D01* -X778Y1051D01* -X778Y1055D01* -X776Y1055D01* -X776Y1057D01* -X772Y1057D01* -X772Y1059D01* -X770Y1059D01* -X770Y1061D01* -X768Y1061D01* -X768Y1063D01* -X766Y1063D01* -X766Y1065D01* -X764Y1065D01* -X764Y1067D01* -X762Y1067D01* -X762Y1069D01* -X760Y1069D01* -X760Y1071D01* -X738Y1071D01* -G37* -D02* -G36* -X622Y1051D02* -X622Y1049D01* -X778Y1049D01* -X778Y1051D01* -X622Y1051D01* -G37* -D02* -G36* -X622Y1051D02* -X622Y1049D01* -X778Y1049D01* -X778Y1051D01* -X622Y1051D01* -G37* -D02* -G36* -X622Y1049D02* -X622Y853D01* -X620Y853D01* -X620Y675D01* -X794Y675D01* -X794Y677D01* -X790Y677D01* -X790Y679D01* -X786Y679D01* -X786Y681D01* -X784Y681D01* -X784Y683D01* -X782Y683D01* -X782Y687D01* -X780Y687D01* -X780Y693D01* -X778Y693D01* -X778Y1049D01* -X622Y1049D01* -G37* -D02* -G36* -X1212Y677D02* -X1212Y675D01* -X1660Y675D01* -X1660Y677D01* -X1212Y677D01* -G37* -D02* -G36* -X620Y675D02* -X620Y673D01* -X1662Y673D01* -X1662Y675D01* -X620Y675D01* -G37* -D02* -G36* -X620Y675D02* -X620Y673D01* -X1662Y673D01* -X1662Y675D01* -X620Y675D01* -G37* -D02* -G36* -X620Y673D02* -X620Y621D01* -X1660Y621D01* -X1660Y623D01* -X1662Y623D01* -X1662Y625D01* -X1664Y625D01* -X1664Y627D01* -X1666Y627D01* -X1666Y631D01* -X1668Y631D01* -X1668Y633D01* -X1672Y633D01* -X1672Y635D01* -X1674Y635D01* -X1674Y637D01* -X1678Y637D01* -X1678Y639D01* -X1680Y639D01* -X1680Y659D01* -X1678Y659D01* -X1678Y661D01* -X1674Y661D01* -X1674Y663D01* -X1672Y663D01* -X1672Y665D01* -X1668Y665D01* -X1668Y667D01* -X1666Y667D01* -X1666Y671D01* -X1664Y671D01* -X1664Y673D01* -X620Y673D01* -G37* -D02* -G36* -X1238Y1671D02* -X1238Y1669D01* -X1236Y1669D01* -X1236Y1665D01* -X1234Y1665D01* -X1234Y1663D01* -X1230Y1663D01* -X1230Y1661D01* -X1228Y1661D01* -X1228Y1659D01* -X1226Y1659D01* -X1226Y1657D01* -X1222Y1657D01* -X1222Y1531D01* -X1220Y1531D01* -X1220Y1191D01* -X1218Y1191D01* -X1218Y1187D01* -X1216Y1187D01* -X1216Y1183D01* -X1214Y1183D01* -X1214Y1181D01* -X1210Y1181D01* -X1210Y1179D01* -X1208Y1179D01* -X1208Y1177D01* -X220Y1177D01* -X220Y1149D01* -X900Y1149D01* -X900Y1147D01* -X912Y1147D01* -X912Y1145D01* -X918Y1145D01* -X918Y1143D01* -X922Y1143D01* -X922Y1141D01* -X926Y1141D01* -X926Y1139D01* -X928Y1139D01* -X928Y1137D01* -X932Y1137D01* -X932Y1135D01* -X934Y1135D01* -X934Y1133D01* -X936Y1133D01* -X936Y1129D01* -X938Y1129D01* -X938Y1127D01* -X940Y1127D01* -X940Y1125D01* -X942Y1125D01* -X942Y1121D01* -X944Y1121D01* -X944Y1117D01* -X946Y1117D01* -X946Y1109D01* -X948Y1109D01* -X948Y1089D01* -X946Y1089D01* -X946Y1081D01* -X944Y1081D01* -X944Y1077D01* -X942Y1077D01* -X942Y1073D01* -X940Y1073D01* -X940Y1071D01* -X938Y1071D01* -X938Y1069D01* -X936Y1069D01* -X936Y1065D01* -X934Y1065D01* -X934Y1063D01* -X930Y1063D01* -X930Y1061D01* -X928Y1061D01* -X928Y1059D01* -X926Y1059D01* -X926Y1057D01* -X922Y1057D01* -X922Y1055D01* -X918Y1055D01* -X918Y1053D01* -X912Y1053D01* -X912Y1051D01* -X1680Y1051D01* -X1680Y1059D01* -X1678Y1059D01* -X1678Y1061D01* -X1674Y1061D01* -X1674Y1063D01* -X1672Y1063D01* -X1672Y1065D01* -X1668Y1065D01* -X1668Y1067D01* -X1666Y1067D01* -X1666Y1071D01* -X1664Y1071D01* -X1664Y1073D01* -X1662Y1073D01* -X1662Y1075D01* -X1660Y1075D01* -X1660Y1077D01* -X1418Y1077D01* -X1418Y1079D01* -X1290Y1079D01* -X1290Y1081D01* -X1286Y1081D01* -X1286Y1083D01* -X1284Y1083D01* -X1284Y1085D01* -X1282Y1085D01* -X1282Y1087D01* -X1280Y1087D01* -X1280Y1091D01* -X1278Y1091D01* -X1278Y1097D01* -X1276Y1097D01* -X1276Y1485D01* -X1278Y1485D01* -X1278Y1655D01* -X1276Y1655D01* -X1276Y1657D01* -X1272Y1657D01* -X1272Y1659D01* -X1270Y1659D01* -X1270Y1661D01* -X1268Y1661D01* -X1268Y1663D01* -X1266Y1663D01* -X1266Y1665D01* -X1264Y1665D01* -X1264Y1667D01* -X1262Y1667D01* -X1262Y1669D01* -X1260Y1669D01* -X1260Y1671D01* -X1238Y1671D01* -G37* -D02* -G36* -X1744Y1577D02* -X1744Y1555D01* -X1724Y1555D01* -X1724Y1535D01* -X1728Y1535D01* -X1728Y1533D01* -X1730Y1533D01* -X1730Y1531D01* -X1732Y1531D01* -X1732Y1529D01* -X1734Y1529D01* -X1734Y1527D01* -X1736Y1527D01* -X1736Y1523D01* -X1738Y1523D01* -X1738Y1519D01* -X1740Y1519D01* -X1740Y1515D01* -X1742Y1515D01* -X1742Y1509D01* -X1744Y1509D01* -X1744Y1489D01* -X1742Y1489D01* -X1742Y1483D01* -X1740Y1483D01* -X1740Y1479D01* -X1738Y1479D01* -X1738Y1475D01* -X1736Y1475D01* -X1736Y1473D01* -X1734Y1473D01* -X1734Y1469D01* -X1732Y1469D01* -X1732Y1467D01* -X1730Y1467D01* -X1730Y1465D01* -X1728Y1465D01* -X1728Y1463D01* -X1724Y1463D01* -X1724Y1461D01* -X1722Y1461D01* -X1722Y1459D01* -X1718Y1459D01* -X1718Y1439D01* -X1722Y1439D01* -X1722Y1437D01* -X1724Y1437D01* -X1724Y1435D01* -X1728Y1435D01* -X1728Y1433D01* -X1730Y1433D01* -X1730Y1431D01* -X1732Y1431D01* -X1732Y1429D01* -X1734Y1429D01* -X1734Y1427D01* -X1736Y1427D01* -X1736Y1423D01* -X1738Y1423D01* -X1738Y1419D01* -X1740Y1419D01* -X1740Y1415D01* -X1742Y1415D01* -X1742Y1409D01* -X1744Y1409D01* -X1744Y1389D01* -X1742Y1389D01* -X1742Y1383D01* -X1740Y1383D01* -X1740Y1379D01* -X1738Y1379D01* -X1738Y1375D01* -X1736Y1375D01* -X1736Y1373D01* -X1734Y1373D01* -X1734Y1369D01* -X1732Y1369D01* -X1732Y1367D01* -X1730Y1367D01* -X1730Y1365D01* -X1728Y1365D01* -X1728Y1363D01* -X1724Y1363D01* -X1724Y1361D01* -X1722Y1361D01* -X1722Y1359D01* -X1718Y1359D01* -X1718Y1339D01* -X1722Y1339D01* -X1722Y1337D01* -X1724Y1337D01* -X1724Y1335D01* -X1728Y1335D01* -X1728Y1333D01* -X1730Y1333D01* -X1730Y1331D01* -X1732Y1331D01* -X1732Y1329D01* -X1734Y1329D01* -X1734Y1327D01* -X1736Y1327D01* -X1736Y1323D01* -X1738Y1323D01* -X1738Y1319D01* -X1740Y1319D01* -X1740Y1315D01* -X1742Y1315D01* -X1742Y1309D01* -X1744Y1309D01* -X1744Y1289D01* -X1742Y1289D01* -X1742Y1283D01* -X1740Y1283D01* -X1740Y1279D01* -X1738Y1279D01* -X1738Y1275D01* -X1736Y1275D01* -X1736Y1273D01* -X1734Y1273D01* -X1734Y1269D01* -X1732Y1269D01* -X1732Y1267D01* -X1730Y1267D01* -X1730Y1265D01* -X1728Y1265D01* -X1728Y1263D01* -X1724Y1263D01* -X1724Y1261D01* -X1722Y1261D01* -X1722Y1259D01* -X1718Y1259D01* -X1718Y1239D01* -X1722Y1239D01* -X1722Y1237D01* -X1724Y1237D01* -X1724Y1235D01* -X1728Y1235D01* -X1728Y1233D01* -X1730Y1233D01* -X1730Y1231D01* -X1732Y1231D01* -X1732Y1229D01* -X1734Y1229D01* -X1734Y1227D01* -X1736Y1227D01* -X1736Y1223D01* -X1738Y1223D01* -X1738Y1219D01* -X1740Y1219D01* -X1740Y1215D01* -X1742Y1215D01* -X1742Y1209D01* -X1744Y1209D01* -X1744Y1189D01* -X1742Y1189D01* -X1742Y1183D01* -X1740Y1183D01* -X1740Y1179D01* -X1738Y1179D01* -X1738Y1175D01* -X1736Y1175D01* -X1736Y1173D01* -X1734Y1173D01* -X1734Y1169D01* -X1732Y1169D01* -X1732Y1167D01* -X1730Y1167D01* -X1730Y1165D01* -X1728Y1165D01* -X1728Y1163D01* -X1724Y1163D01* -X1724Y1161D01* -X1722Y1161D01* -X1722Y1159D01* -X1718Y1159D01* -X1718Y1139D01* -X1722Y1139D01* -X1722Y1137D01* -X1724Y1137D01* -X1724Y1135D01* -X1728Y1135D01* -X1728Y1133D01* -X1730Y1133D01* -X1730Y1131D01* -X1732Y1131D01* -X1732Y1129D01* -X1734Y1129D01* -X1734Y1127D01* -X1736Y1127D01* -X1736Y1123D01* -X1738Y1123D01* -X1738Y1119D01* -X1740Y1119D01* -X1740Y1115D01* -X1742Y1115D01* -X1742Y1109D01* -X1744Y1109D01* -X1744Y1089D01* -X1742Y1089D01* -X1742Y1083D01* -X1740Y1083D01* -X1740Y1079D01* -X1738Y1079D01* -X1738Y1075D01* -X1736Y1075D01* -X1736Y1073D01* -X1734Y1073D01* -X1734Y1069D01* -X1732Y1069D01* -X1732Y1067D01* -X1730Y1067D01* -X1730Y1065D01* -X1728Y1065D01* -X1728Y1063D01* -X1724Y1063D01* -X1724Y1061D01* -X1722Y1061D01* -X1722Y1059D01* -X1718Y1059D01* -X1718Y1039D01* -X1722Y1039D01* -X1722Y1037D01* -X1724Y1037D01* -X1724Y1035D01* -X1728Y1035D01* -X1728Y1033D01* -X1730Y1033D01* -X1730Y1031D01* -X1732Y1031D01* -X1732Y1029D01* -X1734Y1029D01* -X1734Y1027D01* -X1736Y1027D01* -X1736Y1023D01* -X1738Y1023D01* -X1738Y1019D01* -X1740Y1019D01* -X1740Y1015D01* -X1742Y1015D01* -X1742Y1009D01* -X1744Y1009D01* -X1744Y989D01* -X1742Y989D01* -X1742Y983D01* -X1740Y983D01* -X1740Y979D01* -X1738Y979D01* -X1738Y975D01* -X1736Y975D01* -X1736Y973D01* -X1734Y973D01* -X1734Y969D01* -X1732Y969D01* -X1732Y967D01* -X1730Y967D01* -X1730Y965D01* -X1728Y965D01* -X1728Y963D01* -X1724Y963D01* -X1724Y961D01* -X1722Y961D01* -X1722Y959D01* -X1718Y959D01* -X1718Y939D01* -X1722Y939D01* -X1722Y937D01* -X1724Y937D01* -X1724Y935D01* -X1728Y935D01* -X1728Y933D01* -X1730Y933D01* -X1730Y931D01* -X1732Y931D01* -X1732Y929D01* -X1734Y929D01* -X1734Y927D01* -X1736Y927D01* -X1736Y923D01* -X1738Y923D01* -X1738Y919D01* -X1740Y919D01* -X1740Y915D01* -X1742Y915D01* -X1742Y909D01* -X1744Y909D01* -X1744Y889D01* -X1742Y889D01* -X1742Y883D01* -X1740Y883D01* -X1740Y879D01* -X1738Y879D01* -X1738Y875D01* -X1736Y875D01* -X1736Y873D01* -X1734Y873D01* -X1734Y869D01* -X1732Y869D01* -X1732Y867D01* -X1730Y867D01* -X1730Y865D01* -X1728Y865D01* -X1728Y863D01* -X1724Y863D01* -X1724Y861D01* -X1722Y861D01* -X1722Y859D01* -X1718Y859D01* -X1718Y839D01* -X1722Y839D01* -X1722Y837D01* -X1724Y837D01* -X1724Y835D01* -X1728Y835D01* -X1728Y833D01* -X1730Y833D01* -X1730Y831D01* -X1732Y831D01* -X1732Y829D01* -X1734Y829D01* -X1734Y827D01* -X1736Y827D01* -X1736Y823D01* -X1738Y823D01* -X1738Y819D01* -X1740Y819D01* -X1740Y815D01* -X1742Y815D01* -X1742Y809D01* -X1744Y809D01* -X1744Y789D01* -X1742Y789D01* -X1742Y783D01* -X1740Y783D01* -X1740Y779D01* -X1738Y779D01* -X1738Y775D01* -X1736Y775D01* -X1736Y773D01* -X1734Y773D01* -X1734Y769D01* -X1732Y769D01* -X1732Y767D01* -X1730Y767D01* -X1730Y765D01* -X1728Y765D01* -X1728Y763D01* -X1724Y763D01* -X1724Y761D01* -X1722Y761D01* -X1722Y759D01* -X1718Y759D01* -X1718Y739D01* -X1722Y739D01* -X1722Y737D01* -X1724Y737D01* -X1724Y735D01* -X1728Y735D01* -X1728Y733D01* -X1730Y733D01* -X1730Y731D01* -X1732Y731D01* -X1732Y729D01* -X1734Y729D01* -X1734Y727D01* -X1736Y727D01* -X1736Y723D01* -X1738Y723D01* -X1738Y719D01* -X1740Y719D01* -X1740Y715D01* -X1742Y715D01* -X1742Y709D01* -X1744Y709D01* -X1744Y689D01* -X1742Y689D01* -X1742Y683D01* -X1740Y683D01* -X1740Y679D01* -X1738Y679D01* -X1738Y675D01* -X1736Y675D01* -X1736Y673D01* -X1734Y673D01* -X1734Y669D01* -X1732Y669D01* -X1732Y667D01* -X1730Y667D01* -X1730Y665D01* -X1728Y665D01* -X1728Y663D01* -X1724Y663D01* -X1724Y661D01* -X1722Y661D01* -X1722Y659D01* -X1718Y659D01* -X1718Y639D01* -X1722Y639D01* -X1722Y637D01* -X1724Y637D01* -X1724Y635D01* -X1728Y635D01* -X1728Y633D01* -X1730Y633D01* -X1730Y631D01* -X1732Y631D01* -X1732Y629D01* -X1734Y629D01* -X1734Y627D01* -X1736Y627D01* -X1736Y623D01* -X1738Y623D01* -X1738Y619D01* -X1740Y619D01* -X1740Y615D01* -X1742Y615D01* -X1742Y609D01* -X1744Y609D01* -X1744Y589D01* -X1742Y589D01* -X1742Y583D01* -X1740Y583D01* -X1740Y579D01* -X1738Y579D01* -X1738Y575D01* -X1736Y575D01* -X1736Y573D01* -X1734Y573D01* -X1734Y569D01* -X1732Y569D01* -X1732Y567D01* -X1730Y567D01* -X1730Y565D01* -X1728Y565D01* -X1728Y563D01* -X1724Y563D01* -X1724Y561D01* -X1722Y561D01* -X1722Y559D01* -X1718Y559D01* -X1718Y539D01* -X1722Y539D01* -X1722Y537D01* -X1724Y537D01* -X1724Y535D01* -X1728Y535D01* -X1728Y533D01* -X1730Y533D01* -X1730Y531D01* -X1732Y531D01* -X1732Y529D01* -X1734Y529D01* -X1734Y527D01* -X1736Y527D01* -X1736Y523D01* -X1738Y523D01* -X1738Y519D01* -X1740Y519D01* -X1740Y515D01* -X1742Y515D01* -X1742Y509D01* -X1744Y509D01* -X1744Y489D01* -X1742Y489D01* -X1742Y483D01* -X1740Y483D01* -X1740Y479D01* -X1738Y479D01* -X1738Y475D01* -X1736Y475D01* -X1736Y473D01* -X1734Y473D01* -X1734Y469D01* -X1732Y469D01* -X1732Y467D01* -X1730Y467D01* -X1730Y465D01* -X1728Y465D01* -X1728Y463D01* -X1724Y463D01* -X1724Y461D01* -X1722Y461D01* -X1722Y459D01* -X1718Y459D01* -X1718Y439D01* -X1722Y439D01* -X1722Y437D01* -X1724Y437D01* -X1724Y435D01* -X1728Y435D01* -X1728Y433D01* -X1730Y433D01* -X1730Y431D01* -X1732Y431D01* -X1732Y429D01* -X1734Y429D01* -X1734Y427D01* -X1736Y427D01* -X1736Y423D01* -X1738Y423D01* -X1738Y419D01* -X1740Y419D01* -X1740Y415D01* -X1742Y415D01* -X1742Y409D01* -X1744Y409D01* -X1744Y389D01* -X1742Y389D01* -X1742Y383D01* -X1740Y383D01* -X1740Y379D01* -X1738Y379D01* -X1738Y375D01* -X1736Y375D01* -X1736Y373D01* -X1734Y373D01* -X1734Y369D01* -X1732Y369D01* -X1732Y367D01* -X1730Y367D01* -X1730Y365D01* -X1728Y365D01* -X1728Y363D01* -X1724Y363D01* -X1724Y361D01* -X1722Y361D01* -X1722Y359D01* -X1718Y359D01* -X1718Y339D01* -X1722Y339D01* -X1722Y337D01* -X1724Y337D01* -X1724Y335D01* -X1728Y335D01* -X1728Y333D01* -X1730Y333D01* -X1730Y331D01* -X1732Y331D01* -X1732Y329D01* -X1734Y329D01* -X1734Y327D01* -X1736Y327D01* -X1736Y323D01* -X1738Y323D01* -X1738Y319D01* -X1740Y319D01* -X1740Y315D01* -X1742Y315D01* -X1742Y309D01* -X1744Y309D01* -X1744Y289D01* -X1742Y289D01* -X1742Y283D01* -X1740Y283D01* -X1740Y279D01* -X1738Y279D01* -X1738Y275D01* -X1736Y275D01* -X1736Y273D01* -X1734Y273D01* -X1734Y269D01* -X1732Y269D01* -X1732Y267D01* -X1730Y267D01* -X1730Y265D01* -X1728Y265D01* -X1728Y263D01* -X1724Y263D01* -X1724Y261D01* -X1722Y261D01* -X1722Y259D01* -X1718Y259D01* -X1718Y239D01* -X1722Y239D01* -X1722Y237D01* -X1724Y237D01* -X1724Y235D01* -X1728Y235D01* -X1728Y233D01* -X1730Y233D01* -X1730Y231D01* -X1732Y231D01* -X1732Y229D01* -X1734Y229D01* -X1734Y227D01* -X1736Y227D01* -X1736Y223D01* -X1738Y223D01* -X1738Y219D01* -X1740Y219D01* -X1740Y215D01* -X1742Y215D01* -X1742Y209D01* -X1744Y209D01* -X1744Y189D01* -X1742Y189D01* -X1742Y183D01* -X1740Y183D01* -X1740Y179D01* -X1738Y179D01* -X1738Y175D01* -X1736Y175D01* -X1736Y173D01* -X1734Y173D01* -X1734Y169D01* -X1732Y169D01* -X1732Y167D01* -X1730Y167D01* -X1730Y165D01* -X1728Y165D01* -X1728Y163D01* -X1724Y163D01* -X1724Y161D01* -X1722Y161D01* -X1722Y159D01* -X1718Y159D01* -X1718Y157D01* -X1712Y157D01* -X1712Y155D01* -X1776Y155D01* -X1776Y1577D01* -X1744Y1577D01* -G37* -D02* -G36* -X220Y1149D02* -X220Y1051D01* -X386Y1051D01* -X386Y1053D01* -X380Y1053D01* -X380Y1055D01* -X376Y1055D01* -X376Y1057D01* -X372Y1057D01* -X372Y1059D01* -X370Y1059D01* -X370Y1061D01* -X368Y1061D01* -X368Y1063D01* -X366Y1063D01* -X366Y1065D01* -X364Y1065D01* -X364Y1067D01* -X362Y1067D01* -X362Y1069D01* -X360Y1069D01* -X360Y1071D01* -X358Y1071D01* -X358Y1075D01* -X356Y1075D01* -X356Y1079D01* -X354Y1079D01* -X354Y1083D01* -X352Y1083D01* -X352Y1091D01* -X350Y1091D01* -X350Y1107D01* -X352Y1107D01* -X352Y1115D01* -X354Y1115D01* -X354Y1119D01* -X356Y1119D01* -X356Y1123D01* -X358Y1123D01* -X358Y1127D01* -X360Y1127D01* -X360Y1129D01* -X362Y1129D01* -X362Y1131D01* -X364Y1131D01* -X364Y1133D01* -X366Y1133D01* -X366Y1135D01* -X368Y1135D01* -X368Y1137D01* -X370Y1137D01* -X370Y1139D01* -X372Y1139D01* -X372Y1141D01* -X376Y1141D01* -X376Y1143D01* -X380Y1143D01* -X380Y1145D01* -X386Y1145D01* -X386Y1147D01* -X398Y1147D01* -X398Y1149D01* -X220Y1149D01* -G37* -D02* -G36* -X400Y1149D02* -X400Y1147D01* -X412Y1147D01* -X412Y1145D01* -X418Y1145D01* -X418Y1143D01* -X422Y1143D01* -X422Y1141D01* -X426Y1141D01* -X426Y1139D01* -X428Y1139D01* -X428Y1137D01* -X432Y1137D01* -X432Y1135D01* -X434Y1135D01* -X434Y1133D01* -X436Y1133D01* -X436Y1129D01* -X438Y1129D01* -X438Y1127D01* -X460Y1127D01* -X460Y1129D01* -X462Y1129D01* -X462Y1131D01* -X464Y1131D01* -X464Y1133D01* -X466Y1133D01* -X466Y1135D01* -X468Y1135D01* -X468Y1137D01* -X470Y1137D01* -X470Y1139D01* -X472Y1139D01* -X472Y1141D01* -X476Y1141D01* -X476Y1143D01* -X480Y1143D01* -X480Y1145D01* -X486Y1145D01* -X486Y1147D01* -X498Y1147D01* -X498Y1149D01* -X400Y1149D01* -G37* -D02* -G36* -X500Y1149D02* -X500Y1147D01* -X512Y1147D01* -X512Y1145D01* -X518Y1145D01* -X518Y1143D01* -X522Y1143D01* -X522Y1141D01* -X526Y1141D01* -X526Y1139D01* -X528Y1139D01* -X528Y1137D01* -X532Y1137D01* -X532Y1135D01* -X534Y1135D01* -X534Y1133D01* -X536Y1133D01* -X536Y1129D01* -X538Y1129D01* -X538Y1127D01* -X560Y1127D01* -X560Y1129D01* -X562Y1129D01* -X562Y1131D01* -X564Y1131D01* -X564Y1133D01* -X566Y1133D01* -X566Y1135D01* -X568Y1135D01* -X568Y1137D01* -X570Y1137D01* -X570Y1139D01* -X572Y1139D01* -X572Y1141D01* -X576Y1141D01* -X576Y1143D01* -X580Y1143D01* -X580Y1145D01* -X586Y1145D01* -X586Y1147D01* -X598Y1147D01* -X598Y1149D01* -X500Y1149D01* -G37* -D02* -G36* -X600Y1149D02* -X600Y1147D01* -X612Y1147D01* -X612Y1145D01* -X618Y1145D01* -X618Y1143D01* -X622Y1143D01* -X622Y1141D01* -X626Y1141D01* -X626Y1139D01* -X628Y1139D01* -X628Y1137D01* -X632Y1137D01* -X632Y1135D01* -X634Y1135D01* -X634Y1133D01* -X636Y1133D01* -X636Y1129D01* -X638Y1129D01* -X638Y1127D01* -X660Y1127D01* -X660Y1129D01* -X662Y1129D01* -X662Y1131D01* -X664Y1131D01* -X664Y1133D01* -X666Y1133D01* -X666Y1135D01* -X668Y1135D01* -X668Y1137D01* -X670Y1137D01* -X670Y1139D01* -X672Y1139D01* -X672Y1141D01* -X676Y1141D01* -X676Y1143D01* -X680Y1143D01* -X680Y1145D01* -X686Y1145D01* -X686Y1147D01* -X698Y1147D01* -X698Y1149D01* -X600Y1149D01* -G37* -D02* -G36* -X700Y1149D02* -X700Y1147D01* -X712Y1147D01* -X712Y1145D01* -X718Y1145D01* -X718Y1143D01* -X722Y1143D01* -X722Y1141D01* -X726Y1141D01* -X726Y1139D01* -X728Y1139D01* -X728Y1137D01* -X732Y1137D01* -X732Y1135D01* -X734Y1135D01* -X734Y1133D01* -X736Y1133D01* -X736Y1129D01* -X738Y1129D01* -X738Y1127D01* -X760Y1127D01* -X760Y1129D01* -X762Y1129D01* -X762Y1131D01* -X764Y1131D01* -X764Y1133D01* -X766Y1133D01* -X766Y1135D01* -X768Y1135D01* -X768Y1137D01* -X770Y1137D01* -X770Y1139D01* -X772Y1139D01* -X772Y1141D01* -X776Y1141D01* -X776Y1143D01* -X780Y1143D01* -X780Y1145D01* -X786Y1145D01* -X786Y1147D01* -X798Y1147D01* -X798Y1149D01* -X700Y1149D01* -G37* -D02* -G36* -X800Y1149D02* -X800Y1147D01* -X812Y1147D01* -X812Y1145D01* -X818Y1145D01* -X818Y1143D01* -X822Y1143D01* -X822Y1141D01* -X826Y1141D01* -X826Y1139D01* -X828Y1139D01* -X828Y1137D01* -X832Y1137D01* -X832Y1135D01* -X834Y1135D01* -X834Y1133D01* -X836Y1133D01* -X836Y1129D01* -X838Y1129D01* -X838Y1127D01* -X860Y1127D01* -X860Y1129D01* -X862Y1129D01* -X862Y1131D01* -X864Y1131D01* -X864Y1133D01* -X866Y1133D01* -X866Y1135D01* -X868Y1135D01* -X868Y1137D01* -X870Y1137D01* -X870Y1139D01* -X872Y1139D01* -X872Y1141D01* -X876Y1141D01* -X876Y1143D01* -X880Y1143D01* -X880Y1145D01* -X886Y1145D01* -X886Y1147D01* -X898Y1147D01* -X898Y1149D01* -X800Y1149D01* -G37* -D02* -G36* -X438Y1071D02* -X438Y1069D01* -X436Y1069D01* -X436Y1065D01* -X434Y1065D01* -X434Y1063D01* -X430Y1063D01* -X430Y1061D01* -X428Y1061D01* -X428Y1059D01* -X426Y1059D01* -X426Y1057D01* -X422Y1057D01* -X422Y1055D01* -X418Y1055D01* -X418Y1053D01* -X412Y1053D01* -X412Y1051D01* -X486Y1051D01* -X486Y1053D01* -X480Y1053D01* -X480Y1055D01* -X476Y1055D01* -X476Y1057D01* -X472Y1057D01* -X472Y1059D01* -X470Y1059D01* -X470Y1061D01* -X468Y1061D01* -X468Y1063D01* -X466Y1063D01* -X466Y1065D01* -X464Y1065D01* -X464Y1067D01* -X462Y1067D01* -X462Y1069D01* -X460Y1069D01* -X460Y1071D01* -X438Y1071D01* -G37* -D02* -G36* -X538Y1071D02* -X538Y1069D01* -X536Y1069D01* -X536Y1065D01* -X534Y1065D01* -X534Y1063D01* -X530Y1063D01* -X530Y1061D01* -X528Y1061D01* -X528Y1059D01* -X526Y1059D01* -X526Y1057D01* -X522Y1057D01* -X522Y1055D01* -X518Y1055D01* -X518Y1053D01* -X512Y1053D01* -X512Y1051D01* -X578Y1051D01* -X578Y1055D01* -X576Y1055D01* -X576Y1057D01* -X572Y1057D01* -X572Y1059D01* -X570Y1059D01* -X570Y1061D01* -X568Y1061D01* -X568Y1063D01* -X566Y1063D01* -X566Y1065D01* -X564Y1065D01* -X564Y1067D01* -X562Y1067D01* -X562Y1069D01* -X560Y1069D01* -X560Y1071D01* -X538Y1071D01* -G37* -D02* -G36* -X838Y1071D02* -X838Y1069D01* -X836Y1069D01* -X836Y1065D01* -X834Y1065D01* -X834Y1063D01* -X830Y1063D01* -X830Y1061D01* -X828Y1061D01* -X828Y1059D01* -X826Y1059D01* -X826Y1057D01* -X822Y1057D01* -X822Y1051D01* -X886Y1051D01* -X886Y1053D01* -X880Y1053D01* -X880Y1055D01* -X876Y1055D01* -X876Y1057D01* -X872Y1057D01* -X872Y1059D01* -X870Y1059D01* -X870Y1061D01* -X868Y1061D01* -X868Y1063D01* -X866Y1063D01* -X866Y1065D01* -X864Y1065D01* -X864Y1067D01* -X862Y1067D01* -X862Y1069D01* -X860Y1069D01* -X860Y1071D01* -X838Y1071D01* -G37* -D02* -G36* -X220Y1051D02* -X220Y1049D01* -X578Y1049D01* -X578Y1051D01* -X220Y1051D01* -G37* -D02* -G36* -X220Y1051D02* -X220Y1049D01* -X578Y1049D01* -X578Y1051D01* -X220Y1051D01* -G37* -D02* -G36* -X220Y1051D02* -X220Y1049D01* -X578Y1049D01* -X578Y1051D01* -X220Y1051D01* -G37* -D02* -G36* -X822Y1051D02* -X822Y1049D01* -X1680Y1049D01* -X1680Y1051D01* -X822Y1051D01* -G37* -D02* -G36* -X822Y1051D02* -X822Y1049D01* -X1680Y1049D01* -X1680Y1051D01* -X822Y1051D01* -G37* -D02* -G36* -X220Y1049D02* -X220Y421D01* -X1606Y421D01* -X1606Y419D01* -X1610Y419D01* -X1610Y417D01* -X1614Y417D01* -X1614Y415D01* -X1616Y415D01* -X1616Y413D01* -X1618Y413D01* -X1618Y411D01* -X1620Y411D01* -X1620Y405D01* -X1622Y405D01* -X1622Y155D01* -X1688Y155D01* -X1688Y157D01* -X1682Y157D01* -X1682Y159D01* -X1678Y159D01* -X1678Y161D01* -X1674Y161D01* -X1674Y163D01* -X1672Y163D01* -X1672Y165D01* -X1668Y165D01* -X1668Y167D01* -X1666Y167D01* -X1666Y171D01* -X1664Y171D01* -X1664Y173D01* -X1662Y173D01* -X1662Y175D01* -X1660Y175D01* -X1660Y179D01* -X1658Y179D01* -X1658Y185D01* -X1656Y185D01* -X1656Y191D01* -X1654Y191D01* -X1654Y207D01* -X1656Y207D01* -X1656Y213D01* -X1658Y213D01* -X1658Y219D01* -X1660Y219D01* -X1660Y223D01* -X1662Y223D01* -X1662Y225D01* -X1664Y225D01* -X1664Y227D01* -X1666Y227D01* -X1666Y231D01* -X1668Y231D01* -X1668Y233D01* -X1672Y233D01* -X1672Y235D01* -X1674Y235D01* -X1674Y237D01* -X1678Y237D01* -X1678Y239D01* -X1680Y239D01* -X1680Y259D01* -X1678Y259D01* -X1678Y261D01* -X1674Y261D01* -X1674Y263D01* -X1672Y263D01* -X1672Y265D01* -X1668Y265D01* -X1668Y267D01* -X1666Y267D01* -X1666Y271D01* -X1664Y271D01* -X1664Y273D01* -X1662Y273D01* -X1662Y275D01* -X1660Y275D01* -X1660Y279D01* -X1658Y279D01* -X1658Y285D01* -X1656Y285D01* -X1656Y291D01* -X1654Y291D01* -X1654Y307D01* -X1656Y307D01* -X1656Y313D01* -X1658Y313D01* -X1658Y319D01* -X1660Y319D01* -X1660Y323D01* -X1662Y323D01* -X1662Y325D01* -X1664Y325D01* -X1664Y327D01* -X1666Y327D01* -X1666Y331D01* -X1668Y331D01* -X1668Y333D01* -X1672Y333D01* -X1672Y335D01* -X1674Y335D01* -X1674Y337D01* -X1678Y337D01* -X1678Y339D01* -X1680Y339D01* -X1680Y359D01* -X1678Y359D01* -X1678Y361D01* -X1674Y361D01* -X1674Y363D01* -X1672Y363D01* -X1672Y365D01* -X1668Y365D01* -X1668Y367D01* -X1666Y367D01* -X1666Y371D01* -X1664Y371D01* -X1664Y373D01* -X1662Y373D01* -X1662Y375D01* -X1660Y375D01* -X1660Y379D01* -X1658Y379D01* -X1658Y385D01* -X1656Y385D01* -X1656Y391D01* -X1654Y391D01* -X1654Y407D01* -X1656Y407D01* -X1656Y413D01* -X1658Y413D01* -X1658Y419D01* -X1660Y419D01* -X1660Y423D01* -X1662Y423D01* -X1662Y425D01* -X1664Y425D01* -X1664Y427D01* -X1666Y427D01* -X1666Y431D01* -X1668Y431D01* -X1668Y433D01* -X1672Y433D01* -X1672Y435D01* -X1674Y435D01* -X1674Y437D01* -X1678Y437D01* -X1678Y439D01* -X1680Y439D01* -X1680Y459D01* -X1678Y459D01* -X1678Y461D01* -X1674Y461D01* -X1674Y463D01* -X1672Y463D01* -X1672Y465D01* -X1668Y465D01* -X1668Y467D01* -X1666Y467D01* -X1666Y471D01* -X1664Y471D01* -X1664Y473D01* -X1662Y473D01* -X1662Y475D01* -X1660Y475D01* -X1660Y479D01* -X1658Y479D01* -X1658Y485D01* -X1656Y485D01* -X1656Y491D01* -X1654Y491D01* -X1654Y507D01* -X1656Y507D01* -X1656Y513D01* -X1658Y513D01* -X1658Y519D01* -X1660Y519D01* -X1660Y523D01* -X1662Y523D01* -X1662Y525D01* -X1664Y525D01* -X1664Y527D01* -X1666Y527D01* -X1666Y531D01* -X1668Y531D01* -X1668Y533D01* -X1672Y533D01* -X1672Y535D01* -X1674Y535D01* -X1674Y537D01* -X1678Y537D01* -X1678Y539D01* -X1680Y539D01* -X1680Y559D01* -X1678Y559D01* -X1678Y561D01* -X1674Y561D01* -X1674Y563D01* -X1672Y563D01* -X1672Y565D01* -X1668Y565D01* -X1668Y567D01* -X1666Y567D01* -X1666Y571D01* -X1664Y571D01* -X1664Y573D01* -X1662Y573D01* -X1662Y575D01* -X1660Y575D01* -X1660Y577D01* -X590Y577D01* -X590Y579D01* -X586Y579D01* -X586Y581D01* -X584Y581D01* -X584Y583D01* -X582Y583D01* -X582Y585D01* -X580Y585D01* -X580Y589D01* -X578Y589D01* -X578Y595D01* -X576Y595D01* -X576Y861D01* -X578Y861D01* -X578Y1049D01* -X220Y1049D01* -G37* -D02* -G36* -X822Y1049D02* -X822Y719D01* -X1206Y719D01* -X1206Y721D01* -X1660Y721D01* -X1660Y723D01* -X1662Y723D01* -X1662Y725D01* -X1664Y725D01* -X1664Y727D01* -X1666Y727D01* -X1666Y731D01* -X1668Y731D01* -X1668Y733D01* -X1672Y733D01* -X1672Y735D01* -X1674Y735D01* -X1674Y737D01* -X1678Y737D01* -X1678Y739D01* -X1680Y739D01* -X1680Y759D01* -X1678Y759D01* -X1678Y761D01* -X1674Y761D01* -X1674Y763D01* -X1672Y763D01* -X1672Y765D01* -X1668Y765D01* -X1668Y767D01* -X1666Y767D01* -X1666Y771D01* -X1664Y771D01* -X1664Y773D01* -X1662Y773D01* -X1662Y775D01* -X1660Y775D01* -X1660Y779D01* -X1658Y779D01* -X1658Y785D01* -X1656Y785D01* -X1656Y791D01* -X1654Y791D01* -X1654Y807D01* -X1656Y807D01* -X1656Y813D01* -X1658Y813D01* -X1658Y819D01* -X1660Y819D01* -X1660Y823D01* -X1662Y823D01* -X1662Y825D01* -X1664Y825D01* -X1664Y827D01* -X1666Y827D01* -X1666Y831D01* -X1668Y831D01* -X1668Y833D01* -X1672Y833D01* -X1672Y835D01* -X1674Y835D01* -X1674Y837D01* -X1678Y837D01* -X1678Y839D01* -X1680Y839D01* -X1680Y859D01* -X1678Y859D01* -X1678Y861D01* -X1674Y861D01* -X1674Y863D01* -X1672Y863D01* -X1672Y865D01* -X1668Y865D01* -X1668Y867D01* -X1666Y867D01* -X1666Y871D01* -X1664Y871D01* -X1664Y873D01* -X1662Y873D01* -X1662Y875D01* -X1660Y875D01* -X1660Y879D01* -X1658Y879D01* -X1658Y885D01* -X1656Y885D01* -X1656Y891D01* -X1654Y891D01* -X1654Y907D01* -X1656Y907D01* -X1656Y913D01* -X1658Y913D01* -X1658Y919D01* -X1660Y919D01* -X1660Y923D01* -X1662Y923D01* -X1662Y925D01* -X1664Y925D01* -X1664Y927D01* -X1666Y927D01* -X1666Y931D01* -X1668Y931D01* -X1668Y933D01* -X1672Y933D01* -X1672Y935D01* -X1674Y935D01* -X1674Y937D01* -X1678Y937D01* -X1678Y939D01* -X1680Y939D01* -X1680Y959D01* -X1678Y959D01* -X1678Y961D01* -X1674Y961D01* -X1674Y963D01* -X1672Y963D01* -X1672Y965D01* -X1668Y965D01* -X1668Y967D01* -X1666Y967D01* -X1666Y971D01* -X1664Y971D01* -X1664Y973D01* -X1662Y973D01* -X1662Y975D01* -X1660Y975D01* -X1660Y979D01* -X1658Y979D01* -X1658Y985D01* -X1656Y985D01* -X1656Y991D01* -X1654Y991D01* -X1654Y1007D01* -X1656Y1007D01* -X1656Y1013D01* -X1658Y1013D01* -X1658Y1019D01* -X1660Y1019D01* -X1660Y1023D01* -X1662Y1023D01* -X1662Y1025D01* -X1664Y1025D01* -X1664Y1027D01* -X1666Y1027D01* -X1666Y1031D01* -X1668Y1031D01* -X1668Y1033D01* -X1672Y1033D01* -X1672Y1035D01* -X1674Y1035D01* -X1674Y1037D01* -X1678Y1037D01* -X1678Y1039D01* -X1680Y1039D01* -X1680Y1049D01* -X822Y1049D01* -G37* -D02* -G36* -X1622Y155D02* -X1622Y153D01* -X1776Y153D01* -X1776Y155D01* -X1622Y155D01* -G37* -D02* -G36* -X1622Y155D02* -X1622Y153D01* -X1776Y153D01* -X1776Y155D01* -X1622Y155D01* -G37* -D02* -G36* -X1622Y153D02* -X1622Y121D01* -X1776Y121D01* -X1776Y153D01* -X1622Y153D01* -G37* -D02* -G04 End of Copper0* -M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperTop.gtl b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperTop.gtl deleted file mode 100644 index f36c772..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_copperTop.gtl +++ /dev/null @@ -1,4718 +0,0 @@ -G04 MADE WITH FRITZING* -G04 WWW.FRITZING.ORG* -G04 DOUBLE SIDED* -G04 HOLES PLATED* -G04 CONTOUR ON CENTER OF CONTOUR VECTOR* -%ASAXBY*% -%FSLAX23Y23*% -%MOIN*% -%OFA0B0*% -%SFA1.0B1.0*% -%ADD10C,0.075000*% -%ADD11C,0.070000*% -%ADD12C,0.078000*% -%ADD13R,0.069972X0.070000*% -%ADD14C,0.024000*% -%LNCOPPER1*% -G90* -G70* -G54D10* -X1794Y1593D03* -X423Y1693D03* -G54D11* -X1699Y1599D03* -X1699Y1499D03* -X1699Y1399D03* -X1699Y1299D03* -X1699Y1199D03* -X1699Y1099D03* -X1699Y999D03* -X1699Y899D03* -X1699Y799D03* -X1699Y699D03* -X1699Y599D03* -X1699Y499D03* -X1699Y399D03* -X1699Y299D03* -X1699Y199D03* -X2299Y1599D03* -X2299Y1499D03* -X2299Y1399D03* -X2299Y1299D03* -X2299Y1199D03* -X2299Y1099D03* -X2299Y999D03* -X2299Y899D03* -X2299Y799D03* -X2299Y699D03* -X2299Y599D03* -X2299Y499D03* -X2299Y399D03* -X2299Y299D03* -X2299Y199D03* -G54D12* -X1199Y1699D03* -X1299Y1699D03* -X1399Y1699D03* -X1499Y1699D03* -X1199Y99D03* -X1299Y99D03* -X1399Y99D03* -X1499Y99D03* -X399Y1099D03* -X499Y1099D03* -X599Y1099D03* -X699Y1099D03* -X799Y1099D03* -X899Y1099D03* -X299Y1699D03* -X299Y1599D03* -X999Y1699D03* -X999Y1599D03* -G54D13* -X1699Y1599D03* -G54D14* -X500Y100D02* -X499Y1080D01* -D02* -X1180Y99D02* -X500Y100D01* -D02* -X2200Y1500D02* -X2200Y1697D01* -D02* -X2200Y1697D02* -X1599Y1697D01* -D02* -X1599Y199D02* -X1200Y199D01* -D02* -X1200Y199D02* -X1199Y118D01* -D02* -X1599Y1697D02* -X1599Y199D01* -D02* -X2281Y1499D02* -X2200Y1500D01* -D02* -X2200Y1298D02* -X2281Y1299D01* -D02* -X2200Y100D02* -X2200Y1298D01* -D02* -X1518Y99D02* -X2200Y100D01* -G36* -X1622Y1675D02* -X1622Y1645D01* -X1744Y1645D01* -X1744Y1555D01* -X1724Y1555D01* -X1724Y1535D01* -X1728Y1535D01* -X1728Y1533D01* -X1730Y1533D01* -X1730Y1531D01* -X1732Y1531D01* -X1732Y1529D01* -X1734Y1529D01* -X1734Y1527D01* -X1736Y1527D01* -X1736Y1523D01* -X1738Y1523D01* -X1738Y1519D01* -X1740Y1519D01* -X1740Y1515D01* -X1742Y1515D01* -X1742Y1509D01* -X1744Y1509D01* -X1744Y1489D01* -X1742Y1489D01* -X1742Y1483D01* -X1740Y1483D01* -X1740Y1479D01* -X1738Y1479D01* -X1738Y1475D01* -X1736Y1475D01* -X1736Y1473D01* -X1734Y1473D01* -X1734Y1469D01* -X1732Y1469D01* -X1732Y1467D01* -X1730Y1467D01* -X1730Y1465D01* -X1728Y1465D01* -X1728Y1463D01* -X1724Y1463D01* -X1724Y1461D01* -X1722Y1461D01* -X1722Y1459D01* -X1718Y1459D01* -X1718Y1439D01* -X1722Y1439D01* -X1722Y1437D01* -X1724Y1437D01* -X1724Y1435D01* -X1728Y1435D01* -X1728Y1433D01* -X1730Y1433D01* -X1730Y1431D01* -X1732Y1431D01* -X1732Y1429D01* -X1734Y1429D01* -X1734Y1427D01* -X1736Y1427D01* -X1736Y1423D01* -X1738Y1423D01* -X1738Y1419D01* -X1740Y1419D01* -X1740Y1415D01* -X1742Y1415D01* -X1742Y1409D01* -X1744Y1409D01* -X1744Y1389D01* -X1742Y1389D01* -X1742Y1383D01* -X1740Y1383D01* -X1740Y1379D01* -X1738Y1379D01* -X1738Y1375D01* -X1736Y1375D01* -X1736Y1373D01* -X1734Y1373D01* -X1734Y1369D01* -X1732Y1369D01* -X1732Y1367D01* -X1730Y1367D01* -X1730Y1365D01* -X1728Y1365D01* -X1728Y1363D01* -X1724Y1363D01* -X1724Y1361D01* -X1722Y1361D01* -X1722Y1359D01* -X1718Y1359D01* -X1718Y1339D01* -X1722Y1339D01* -X1722Y1337D01* -X1724Y1337D01* -X1724Y1335D01* -X1728Y1335D01* -X1728Y1333D01* -X1730Y1333D01* -X1730Y1331D01* -X1732Y1331D01* -X1732Y1329D01* -X1734Y1329D01* -X1734Y1327D01* -X1736Y1327D01* -X1736Y1323D01* -X1738Y1323D01* -X1738Y1319D01* -X1740Y1319D01* -X1740Y1315D01* -X1742Y1315D01* -X1742Y1309D01* -X1744Y1309D01* -X1744Y1289D01* -X1742Y1289D01* -X1742Y1283D01* -X1740Y1283D01* -X1740Y1279D01* -X1738Y1279D01* -X1738Y1275D01* -X1736Y1275D01* -X1736Y1273D01* -X1734Y1273D01* -X1734Y1269D01* -X1732Y1269D01* -X1732Y1267D01* -X1730Y1267D01* -X1730Y1265D01* -X1728Y1265D01* -X1728Y1263D01* -X1724Y1263D01* -X1724Y1261D01* -X1722Y1261D01* -X1722Y1259D01* -X1718Y1259D01* -X1718Y1239D01* -X1722Y1239D01* -X1722Y1237D01* -X1724Y1237D01* -X1724Y1235D01* -X1728Y1235D01* -X1728Y1233D01* -X1730Y1233D01* -X1730Y1231D01* -X1732Y1231D01* -X1732Y1229D01* -X1734Y1229D01* -X1734Y1227D01* -X1736Y1227D01* -X1736Y1223D01* -X1738Y1223D01* -X1738Y1219D01* -X1740Y1219D01* -X1740Y1215D01* -X1742Y1215D01* -X1742Y1209D01* -X1744Y1209D01* -X1744Y1189D01* -X1742Y1189D01* -X1742Y1183D01* -X1740Y1183D01* -X1740Y1179D01* -X1738Y1179D01* -X1738Y1175D01* -X1736Y1175D01* -X1736Y1173D01* -X1734Y1173D01* -X1734Y1169D01* -X1732Y1169D01* -X1732Y1167D01* -X1730Y1167D01* -X1730Y1165D01* -X1728Y1165D01* -X1728Y1163D01* -X1724Y1163D01* -X1724Y1161D01* -X1722Y1161D01* -X1722Y1159D01* -X1718Y1159D01* -X1718Y1139D01* -X1722Y1139D01* -X1722Y1137D01* -X1724Y1137D01* -X1724Y1135D01* -X1728Y1135D01* -X1728Y1133D01* -X1730Y1133D01* -X1730Y1131D01* -X1732Y1131D01* -X1732Y1129D01* -X1734Y1129D01* -X1734Y1127D01* -X1736Y1127D01* -X1736Y1123D01* -X1738Y1123D01* -X1738Y1119D01* -X1740Y1119D01* -X1740Y1115D01* -X1742Y1115D01* -X1742Y1109D01* -X1744Y1109D01* -X1744Y1089D01* -X1742Y1089D01* -X1742Y1083D01* -X1740Y1083D01* -X1740Y1079D01* -X1738Y1079D01* -X1738Y1075D01* -X1736Y1075D01* -X1736Y1073D01* -X1734Y1073D01* -X1734Y1069D01* -X1732Y1069D01* -X1732Y1067D01* -X1730Y1067D01* -X1730Y1065D01* -X1728Y1065D01* -X1728Y1063D01* -X1724Y1063D01* -X1724Y1061D01* -X1722Y1061D01* -X1722Y1059D01* -X1718Y1059D01* -X1718Y1039D01* -X1722Y1039D01* -X1722Y1037D01* -X1724Y1037D01* -X1724Y1035D01* -X1728Y1035D01* -X1728Y1033D01* -X1730Y1033D01* -X1730Y1031D01* -X1732Y1031D01* -X1732Y1029D01* -X1734Y1029D01* -X1734Y1027D01* -X1736Y1027D01* -X1736Y1023D01* -X1738Y1023D01* -X1738Y1019D01* -X1740Y1019D01* -X1740Y1015D01* -X1742Y1015D01* -X1742Y1009D01* -X1744Y1009D01* -X1744Y989D01* -X1742Y989D01* -X1742Y983D01* -X1740Y983D01* -X1740Y979D01* -X1738Y979D01* -X1738Y975D01* -X1736Y975D01* -X1736Y973D01* -X1734Y973D01* -X1734Y969D01* -X1732Y969D01* -X1732Y967D01* -X1730Y967D01* -X1730Y965D01* -X1728Y965D01* -X1728Y963D01* -X1724Y963D01* -X1724Y961D01* -X1722Y961D01* -X1722Y959D01* -X1718Y959D01* -X1718Y939D01* -X1722Y939D01* -X1722Y937D01* -X1724Y937D01* -X1724Y935D01* -X1728Y935D01* -X1728Y933D01* -X1730Y933D01* -X1730Y931D01* -X1732Y931D01* -X1732Y929D01* -X1734Y929D01* -X1734Y927D01* -X1736Y927D01* -X1736Y923D01* -X1738Y923D01* -X1738Y919D01* -X1740Y919D01* -X1740Y915D01* -X1742Y915D01* -X1742Y909D01* -X1744Y909D01* -X1744Y889D01* -X1742Y889D01* -X1742Y883D01* -X1740Y883D01* -X1740Y879D01* -X1738Y879D01* -X1738Y875D01* -X1736Y875D01* -X1736Y873D01* -X1734Y873D01* -X1734Y869D01* -X1732Y869D01* -X1732Y867D01* -X1730Y867D01* -X1730Y865D01* -X1728Y865D01* -X1728Y863D01* -X1724Y863D01* -X1724Y861D01* -X1722Y861D01* -X1722Y859D01* -X1718Y859D01* -X1718Y839D01* -X1722Y839D01* -X1722Y837D01* -X1724Y837D01* -X1724Y835D01* -X1728Y835D01* -X1728Y833D01* -X1730Y833D01* -X1730Y831D01* -X1732Y831D01* -X1732Y829D01* -X1734Y829D01* -X1734Y827D01* -X1736Y827D01* -X1736Y823D01* -X1738Y823D01* -X1738Y819D01* -X1740Y819D01* -X1740Y815D01* -X1742Y815D01* -X1742Y809D01* -X1744Y809D01* -X1744Y789D01* -X1742Y789D01* -X1742Y783D01* -X1740Y783D01* -X1740Y779D01* -X1738Y779D01* -X1738Y775D01* -X1736Y775D01* -X1736Y773D01* -X1734Y773D01* -X1734Y769D01* -X1732Y769D01* -X1732Y767D01* -X1730Y767D01* -X1730Y765D01* -X1728Y765D01* -X1728Y763D01* -X1724Y763D01* -X1724Y761D01* -X1722Y761D01* -X1722Y759D01* -X1718Y759D01* -X1718Y739D01* -X1722Y739D01* -X1722Y737D01* -X1724Y737D01* -X1724Y735D01* -X1728Y735D01* -X1728Y733D01* -X1730Y733D01* -X1730Y731D01* -X1732Y731D01* -X1732Y729D01* -X1734Y729D01* -X1734Y727D01* -X1736Y727D01* -X1736Y723D01* -X1738Y723D01* -X1738Y719D01* -X1740Y719D01* -X1740Y715D01* -X1742Y715D01* -X1742Y709D01* -X1744Y709D01* -X1744Y689D01* -X1742Y689D01* -X1742Y683D01* -X1740Y683D01* -X1740Y679D01* -X1738Y679D01* -X1738Y675D01* -X1736Y675D01* -X1736Y673D01* -X1734Y673D01* -X1734Y669D01* -X1732Y669D01* -X1732Y667D01* -X1730Y667D01* -X1730Y665D01* -X1728Y665D01* -X1728Y663D01* -X1724Y663D01* -X1724Y661D01* -X1722Y661D01* -X1722Y659D01* -X1718Y659D01* -X1718Y639D01* -X1722Y639D01* -X1722Y637D01* -X1724Y637D01* -X1724Y635D01* -X1728Y635D01* -X1728Y633D01* -X1730Y633D01* -X1730Y631D01* -X1732Y631D01* -X1732Y629D01* -X1734Y629D01* -X1734Y627D01* -X1736Y627D01* -X1736Y623D01* -X1738Y623D01* -X1738Y619D01* -X1740Y619D01* -X1740Y615D01* -X1742Y615D01* -X1742Y609D01* -X1744Y609D01* -X1744Y589D01* -X1742Y589D01* -X1742Y583D01* -X1740Y583D01* -X1740Y579D01* -X1738Y579D01* -X1738Y575D01* -X1736Y575D01* -X1736Y573D01* -X1734Y573D01* -X1734Y569D01* -X1732Y569D01* -X1732Y567D01* -X1730Y567D01* -X1730Y565D01* -X1728Y565D01* -X1728Y563D01* -X1724Y563D01* -X1724Y561D01* -X1722Y561D01* -X1722Y559D01* -X1718Y559D01* -X1718Y539D01* -X1722Y539D01* -X1722Y537D01* -X1724Y537D01* -X1724Y535D01* -X1728Y535D01* -X1728Y533D01* -X1730Y533D01* -X1730Y531D01* -X1732Y531D01* -X1732Y529D01* -X1734Y529D01* -X1734Y527D01* -X1736Y527D01* -X1736Y523D01* -X1738Y523D01* -X1738Y519D01* -X1740Y519D01* -X1740Y515D01* -X1742Y515D01* -X1742Y509D01* -X1744Y509D01* -X1744Y489D01* -X1742Y489D01* -X1742Y483D01* -X1740Y483D01* -X1740Y479D01* -X1738Y479D01* -X1738Y475D01* -X1736Y475D01* -X1736Y473D01* -X1734Y473D01* -X1734Y469D01* -X1732Y469D01* -X1732Y467D01* -X1730Y467D01* -X1730Y465D01* -X1728Y465D01* -X1728Y463D01* -X1724Y463D01* -X1724Y461D01* -X1722Y461D01* -X1722Y459D01* -X1718Y459D01* -X1718Y439D01* -X1722Y439D01* -X1722Y437D01* -X1724Y437D01* -X1724Y435D01* -X1728Y435D01* -X1728Y433D01* -X1730Y433D01* -X1730Y431D01* -X1732Y431D01* -X1732Y429D01* -X1734Y429D01* -X1734Y427D01* -X1736Y427D01* -X1736Y423D01* -X1738Y423D01* -X1738Y419D01* -X1740Y419D01* -X1740Y415D01* -X1742Y415D01* -X1742Y409D01* -X1744Y409D01* -X1744Y389D01* -X1742Y389D01* -X1742Y383D01* -X1740Y383D01* -X1740Y379D01* -X1738Y379D01* -X1738Y375D01* -X1736Y375D01* -X1736Y373D01* -X1734Y373D01* -X1734Y369D01* -X1732Y369D01* -X1732Y367D01* -X1730Y367D01* -X1730Y365D01* -X1728Y365D01* -X1728Y363D01* -X1724Y363D01* -X1724Y361D01* -X1722Y361D01* -X1722Y359D01* -X1718Y359D01* -X1718Y339D01* -X1722Y339D01* -X1722Y337D01* -X1724Y337D01* -X1724Y335D01* -X1728Y335D01* -X1728Y333D01* -X1730Y333D01* -X1730Y331D01* -X1732Y331D01* -X1732Y329D01* -X1734Y329D01* -X1734Y327D01* -X1736Y327D01* -X1736Y323D01* -X1738Y323D01* -X1738Y319D01* -X1740Y319D01* -X1740Y315D01* -X1742Y315D01* -X1742Y309D01* -X1744Y309D01* -X1744Y289D01* -X1742Y289D01* -X1742Y283D01* -X1740Y283D01* -X1740Y279D01* -X1738Y279D01* -X1738Y275D01* -X1736Y275D01* -X1736Y273D01* -X1734Y273D01* -X1734Y269D01* -X1732Y269D01* -X1732Y267D01* -X1730Y267D01* -X1730Y265D01* -X1728Y265D01* -X1728Y263D01* -X1724Y263D01* -X1724Y261D01* -X1722Y261D01* -X1722Y259D01* -X1718Y259D01* -X1718Y239D01* -X1722Y239D01* -X1722Y237D01* -X1724Y237D01* -X1724Y235D01* -X1728Y235D01* -X1728Y233D01* -X1730Y233D01* -X1730Y231D01* -X1732Y231D01* -X1732Y229D01* -X1734Y229D01* -X1734Y227D01* -X1736Y227D01* -X1736Y223D01* -X1738Y223D01* -X1738Y219D01* -X1740Y219D01* -X1740Y215D01* -X1742Y215D01* -X1742Y209D01* -X1744Y209D01* -X1744Y189D01* -X1742Y189D01* -X1742Y183D01* -X1740Y183D01* -X1740Y179D01* -X1738Y179D01* -X1738Y175D01* -X1736Y175D01* -X1736Y173D01* -X1734Y173D01* -X1734Y169D01* -X1732Y169D01* -X1732Y167D01* -X1730Y167D01* -X1730Y165D01* -X1728Y165D01* -X1728Y163D01* -X1724Y163D01* -X1724Y161D01* -X1722Y161D01* -X1722Y159D01* -X1718Y159D01* -X1718Y157D01* -X1712Y157D01* -X1712Y155D01* -X2178Y155D01* -X2178Y1305D01* -X2180Y1305D01* -X2180Y1309D01* -X2182Y1309D01* -X2182Y1311D01* -X2184Y1311D01* -X2184Y1315D01* -X2188Y1315D01* -X2188Y1317D01* -X2190Y1317D01* -X2190Y1319D01* -X2198Y1319D01* -X2198Y1321D01* -X2260Y1321D01* -X2260Y1323D01* -X2262Y1323D01* -X2262Y1325D01* -X2264Y1325D01* -X2264Y1327D01* -X2266Y1327D01* -X2266Y1331D01* -X2268Y1331D01* -X2268Y1333D01* -X2272Y1333D01* -X2272Y1335D01* -X2274Y1335D01* -X2274Y1337D01* -X2278Y1337D01* -X2278Y1339D01* -X2280Y1339D01* -X2280Y1359D01* -X2278Y1359D01* -X2278Y1361D01* -X2274Y1361D01* -X2274Y1363D01* -X2272Y1363D01* -X2272Y1365D01* -X2268Y1365D01* -X2268Y1367D01* -X2266Y1367D01* -X2266Y1371D01* -X2264Y1371D01* -X2264Y1373D01* -X2262Y1373D01* -X2262Y1375D01* -X2260Y1375D01* -X2260Y1379D01* -X2258Y1379D01* -X2258Y1385D01* -X2256Y1385D01* -X2256Y1391D01* -X2254Y1391D01* -X2254Y1407D01* -X2256Y1407D01* -X2256Y1413D01* -X2258Y1413D01* -X2258Y1419D01* -X2260Y1419D01* -X2260Y1423D01* -X2262Y1423D01* -X2262Y1425D01* -X2264Y1425D01* -X2264Y1427D01* -X2266Y1427D01* -X2266Y1431D01* -X2268Y1431D01* -X2268Y1433D01* -X2272Y1433D01* -X2272Y1435D01* -X2274Y1435D01* -X2274Y1437D01* -X2278Y1437D01* -X2278Y1439D01* -X2280Y1439D01* -X2280Y1459D01* -X2278Y1459D01* -X2278Y1461D01* -X2274Y1461D01* -X2274Y1463D01* -X2272Y1463D01* -X2272Y1465D01* -X2268Y1465D01* -X2268Y1467D01* -X2266Y1467D01* -X2266Y1471D01* -X2264Y1471D01* -X2264Y1473D01* -X2262Y1473D01* -X2262Y1475D01* -X2260Y1475D01* -X2260Y1477D01* -X2198Y1477D01* -X2198Y1479D01* -X2190Y1479D01* -X2190Y1481D01* -X2188Y1481D01* -X2188Y1483D01* -X2184Y1483D01* -X2184Y1485D01* -X2182Y1485D01* -X2182Y1489D01* -X2180Y1489D01* -X2180Y1493D01* -X2178Y1493D01* -X2178Y1675D01* -X1622Y1675D01* -G37* -D02* -G36* -X1622Y1645D02* -X1622Y199D01* -X1620Y199D01* -X1620Y189D01* -X1618Y189D01* -X1618Y187D01* -X1616Y187D01* -X1616Y183D01* -X1612Y183D01* -X1612Y181D01* -X1610Y181D01* -X1610Y179D01* -X1606Y179D01* -X1606Y177D01* -X1222Y177D01* -X1222Y155D01* -X1688Y155D01* -X1688Y157D01* -X1682Y157D01* -X1682Y159D01* -X1678Y159D01* -X1678Y161D01* -X1674Y161D01* -X1674Y163D01* -X1672Y163D01* -X1672Y165D01* -X1668Y165D01* -X1668Y167D01* -X1666Y167D01* -X1666Y171D01* -X1664Y171D01* -X1664Y173D01* -X1662Y173D01* -X1662Y175D01* -X1660Y175D01* -X1660Y179D01* -X1658Y179D01* -X1658Y185D01* -X1656Y185D01* -X1656Y191D01* -X1654Y191D01* -X1654Y207D01* -X1656Y207D01* -X1656Y213D01* -X1658Y213D01* -X1658Y219D01* -X1660Y219D01* -X1660Y223D01* -X1662Y223D01* -X1662Y225D01* -X1664Y225D01* -X1664Y227D01* -X1666Y227D01* -X1666Y231D01* -X1668Y231D01* -X1668Y233D01* -X1672Y233D01* -X1672Y235D01* -X1674Y235D01* -X1674Y237D01* -X1678Y237D01* -X1678Y239D01* -X1680Y239D01* -X1680Y259D01* -X1678Y259D01* -X1678Y261D01* -X1674Y261D01* -X1674Y263D01* -X1672Y263D01* -X1672Y265D01* -X1668Y265D01* -X1668Y267D01* -X1666Y267D01* -X1666Y271D01* -X1664Y271D01* -X1664Y273D01* -X1662Y273D01* -X1662Y275D01* -X1660Y275D01* -X1660Y279D01* -X1658Y279D01* -X1658Y285D01* -X1656Y285D01* -X1656Y291D01* -X1654Y291D01* -X1654Y307D01* -X1656Y307D01* -X1656Y313D01* -X1658Y313D01* -X1658Y319D01* -X1660Y319D01* -X1660Y323D01* -X1662Y323D01* -X1662Y325D01* -X1664Y325D01* -X1664Y327D01* -X1666Y327D01* -X1666Y331D01* -X1668Y331D01* -X1668Y333D01* -X1672Y333D01* -X1672Y335D01* -X1674Y335D01* -X1674Y337D01* -X1678Y337D01* -X1678Y339D01* -X1680Y339D01* -X1680Y359D01* -X1678Y359D01* -X1678Y361D01* -X1674Y361D01* -X1674Y363D01* -X1672Y363D01* -X1672Y365D01* -X1668Y365D01* -X1668Y367D01* -X1666Y367D01* -X1666Y371D01* -X1664Y371D01* -X1664Y373D01* -X1662Y373D01* -X1662Y375D01* -X1660Y375D01* -X1660Y379D01* -X1658Y379D01* -X1658Y385D01* -X1656Y385D01* -X1656Y391D01* -X1654Y391D01* -X1654Y407D01* -X1656Y407D01* -X1656Y413D01* -X1658Y413D01* -X1658Y419D01* -X1660Y419D01* -X1660Y423D01* -X1662Y423D01* -X1662Y425D01* -X1664Y425D01* -X1664Y427D01* -X1666Y427D01* -X1666Y431D01* -X1668Y431D01* -X1668Y433D01* -X1672Y433D01* -X1672Y435D01* -X1674Y435D01* -X1674Y437D01* -X1678Y437D01* -X1678Y439D01* -X1680Y439D01* -X1680Y459D01* -X1678Y459D01* -X1678Y461D01* -X1674Y461D01* -X1674Y463D01* -X1672Y463D01* -X1672Y465D01* -X1668Y465D01* -X1668Y467D01* -X1666Y467D01* -X1666Y471D01* -X1664Y471D01* -X1664Y473D01* -X1662Y473D01* -X1662Y475D01* -X1660Y475D01* -X1660Y479D01* -X1658Y479D01* -X1658Y485D01* -X1656Y485D01* -X1656Y491D01* -X1654Y491D01* -X1654Y507D01* -X1656Y507D01* -X1656Y513D01* -X1658Y513D01* -X1658Y519D01* -X1660Y519D01* -X1660Y523D01* -X1662Y523D01* -X1662Y525D01* -X1664Y525D01* -X1664Y527D01* -X1666Y527D01* -X1666Y531D01* -X1668Y531D01* -X1668Y533D01* -X1672Y533D01* -X1672Y535D01* -X1674Y535D01* -X1674Y537D01* -X1678Y537D01* -X1678Y539D01* -X1680Y539D01* -X1680Y559D01* -X1678Y559D01* -X1678Y561D01* -X1674Y561D01* -X1674Y563D01* -X1672Y563D01* -X1672Y565D01* -X1668Y565D01* -X1668Y567D01* -X1666Y567D01* -X1666Y571D01* -X1664Y571D01* -X1664Y573D01* -X1662Y573D01* -X1662Y575D01* -X1660Y575D01* -X1660Y579D01* -X1658Y579D01* -X1658Y585D01* -X1656Y585D01* -X1656Y591D01* -X1654Y591D01* -X1654Y607D01* -X1656Y607D01* -X1656Y613D01* -X1658Y613D01* -X1658Y619D01* -X1660Y619D01* -X1660Y623D01* -X1662Y623D01* -X1662Y625D01* -X1664Y625D01* -X1664Y627D01* -X1666Y627D01* -X1666Y631D01* -X1668Y631D01* -X1668Y633D01* -X1672Y633D01* -X1672Y635D01* -X1674Y635D01* -X1674Y637D01* -X1678Y637D01* -X1678Y639D01* -X1680Y639D01* -X1680Y659D01* -X1678Y659D01* -X1678Y661D01* -X1674Y661D01* -X1674Y663D01* -X1672Y663D01* -X1672Y665D01* -X1668Y665D01* -X1668Y667D01* -X1666Y667D01* -X1666Y671D01* -X1664Y671D01* -X1664Y673D01* -X1662Y673D01* -X1662Y675D01* -X1660Y675D01* -X1660Y679D01* -X1658Y679D01* -X1658Y685D01* -X1656Y685D01* -X1656Y691D01* -X1654Y691D01* -X1654Y707D01* -X1656Y707D01* -X1656Y713D01* -X1658Y713D01* -X1658Y719D01* -X1660Y719D01* -X1660Y723D01* -X1662Y723D01* -X1662Y725D01* -X1664Y725D01* -X1664Y727D01* -X1666Y727D01* -X1666Y731D01* -X1668Y731D01* -X1668Y733D01* -X1672Y733D01* -X1672Y735D01* -X1674Y735D01* -X1674Y737D01* -X1678Y737D01* -X1678Y739D01* -X1680Y739D01* -X1680Y759D01* -X1678Y759D01* -X1678Y761D01* -X1674Y761D01* -X1674Y763D01* -X1672Y763D01* -X1672Y765D01* -X1668Y765D01* -X1668Y767D01* -X1666Y767D01* -X1666Y771D01* -X1664Y771D01* -X1664Y773D01* -X1662Y773D01* -X1662Y775D01* -X1660Y775D01* -X1660Y779D01* -X1658Y779D01* -X1658Y785D01* -X1656Y785D01* -X1656Y791D01* -X1654Y791D01* -X1654Y807D01* -X1656Y807D01* -X1656Y813D01* -X1658Y813D01* -X1658Y819D01* -X1660Y819D01* -X1660Y823D01* -X1662Y823D01* -X1662Y825D01* -X1664Y825D01* -X1664Y827D01* -X1666Y827D01* -X1666Y831D01* -X1668Y831D01* -X1668Y833D01* -X1672Y833D01* -X1672Y835D01* -X1674Y835D01* -X1674Y837D01* -X1678Y837D01* -X1678Y839D01* -X1680Y839D01* -X1680Y859D01* -X1678Y859D01* -X1678Y861D01* -X1674Y861D01* -X1674Y863D01* -X1672Y863D01* -X1672Y865D01* -X1668Y865D01* -X1668Y867D01* -X1666Y867D01* -X1666Y871D01* -X1664Y871D01* -X1664Y873D01* -X1662Y873D01* -X1662Y875D01* -X1660Y875D01* -X1660Y879D01* -X1658Y879D01* -X1658Y885D01* -X1656Y885D01* -X1656Y891D01* -X1654Y891D01* -X1654Y907D01* -X1656Y907D01* -X1656Y913D01* -X1658Y913D01* -X1658Y919D01* -X1660Y919D01* -X1660Y923D01* -X1662Y923D01* -X1662Y925D01* -X1664Y925D01* -X1664Y927D01* -X1666Y927D01* -X1666Y931D01* -X1668Y931D01* -X1668Y933D01* -X1672Y933D01* -X1672Y935D01* -X1674Y935D01* -X1674Y937D01* -X1678Y937D01* -X1678Y939D01* -X1680Y939D01* -X1680Y959D01* -X1678Y959D01* -X1678Y961D01* -X1674Y961D01* -X1674Y963D01* -X1672Y963D01* -X1672Y965D01* -X1668Y965D01* -X1668Y967D01* -X1666Y967D01* -X1666Y971D01* -X1664Y971D01* -X1664Y973D01* -X1662Y973D01* -X1662Y975D01* -X1660Y975D01* -X1660Y979D01* -X1658Y979D01* -X1658Y985D01* -X1656Y985D01* -X1656Y991D01* -X1654Y991D01* -X1654Y1007D01* -X1656Y1007D01* -X1656Y1013D01* -X1658Y1013D01* -X1658Y1019D01* -X1660Y1019D01* -X1660Y1023D01* -X1662Y1023D01* -X1662Y1025D01* -X1664Y1025D01* -X1664Y1027D01* -X1666Y1027D01* -X1666Y1031D01* -X1668Y1031D01* -X1668Y1033D01* -X1672Y1033D01* -X1672Y1035D01* -X1674Y1035D01* -X1674Y1037D01* -X1678Y1037D01* -X1678Y1039D01* -X1680Y1039D01* -X1680Y1059D01* -X1678Y1059D01* -X1678Y1061D01* -X1674Y1061D01* -X1674Y1063D01* -X1672Y1063D01* -X1672Y1065D01* -X1668Y1065D01* -X1668Y1067D01* -X1666Y1067D01* -X1666Y1071D01* -X1664Y1071D01* -X1664Y1073D01* -X1662Y1073D01* -X1662Y1075D01* -X1660Y1075D01* -X1660Y1079D01* -X1658Y1079D01* -X1658Y1085D01* -X1656Y1085D01* -X1656Y1091D01* -X1654Y1091D01* -X1654Y1107D01* -X1656Y1107D01* -X1656Y1113D01* -X1658Y1113D01* -X1658Y1119D01* -X1660Y1119D01* -X1660Y1123D01* -X1662Y1123D01* -X1662Y1125D01* -X1664Y1125D01* -X1664Y1127D01* -X1666Y1127D01* -X1666Y1131D01* -X1668Y1131D01* -X1668Y1133D01* -X1672Y1133D01* -X1672Y1135D01* -X1674Y1135D01* -X1674Y1137D01* -X1678Y1137D01* -X1678Y1139D01* -X1680Y1139D01* -X1680Y1159D01* -X1678Y1159D01* -X1678Y1161D01* -X1674Y1161D01* -X1674Y1163D01* -X1672Y1163D01* -X1672Y1165D01* -X1668Y1165D01* -X1668Y1167D01* -X1666Y1167D01* -X1666Y1171D01* -X1664Y1171D01* -X1664Y1173D01* -X1662Y1173D01* -X1662Y1175D01* -X1660Y1175D01* -X1660Y1179D01* -X1658Y1179D01* -X1658Y1185D01* -X1656Y1185D01* -X1656Y1191D01* -X1654Y1191D01* -X1654Y1207D01* -X1656Y1207D01* -X1656Y1213D01* -X1658Y1213D01* -X1658Y1219D01* -X1660Y1219D01* -X1660Y1223D01* -X1662Y1223D01* -X1662Y1225D01* -X1664Y1225D01* -X1664Y1227D01* -X1666Y1227D01* -X1666Y1231D01* -X1668Y1231D01* -X1668Y1233D01* -X1672Y1233D01* -X1672Y1235D01* -X1674Y1235D01* -X1674Y1237D01* -X1678Y1237D01* -X1678Y1239D01* -X1680Y1239D01* -X1680Y1259D01* -X1678Y1259D01* -X1678Y1261D01* -X1674Y1261D01* -X1674Y1263D01* -X1672Y1263D01* -X1672Y1265D01* -X1668Y1265D01* -X1668Y1267D01* -X1666Y1267D01* -X1666Y1271D01* -X1664Y1271D01* -X1664Y1273D01* -X1662Y1273D01* -X1662Y1275D01* -X1660Y1275D01* -X1660Y1279D01* -X1658Y1279D01* -X1658Y1285D01* -X1656Y1285D01* -X1656Y1291D01* -X1654Y1291D01* -X1654Y1307D01* -X1656Y1307D01* -X1656Y1313D01* -X1658Y1313D01* -X1658Y1319D01* -X1660Y1319D01* -X1660Y1323D01* -X1662Y1323D01* -X1662Y1325D01* -X1664Y1325D01* -X1664Y1327D01* -X1666Y1327D01* -X1666Y1331D01* -X1668Y1331D01* -X1668Y1333D01* -X1672Y1333D01* -X1672Y1335D01* -X1674Y1335D01* -X1674Y1337D01* -X1678Y1337D01* -X1678Y1339D01* -X1680Y1339D01* -X1680Y1359D01* -X1678Y1359D01* -X1678Y1361D01* -X1674Y1361D01* -X1674Y1363D01* -X1672Y1363D01* -X1672Y1365D01* -X1668Y1365D01* -X1668Y1367D01* -X1666Y1367D01* -X1666Y1371D01* -X1664Y1371D01* -X1664Y1373D01* -X1662Y1373D01* -X1662Y1375D01* -X1660Y1375D01* -X1660Y1379D01* -X1658Y1379D01* -X1658Y1385D01* -X1656Y1385D01* -X1656Y1391D01* -X1654Y1391D01* -X1654Y1407D01* -X1656Y1407D01* -X1656Y1413D01* -X1658Y1413D01* -X1658Y1419D01* -X1660Y1419D01* -X1660Y1423D01* -X1662Y1423D01* -X1662Y1425D01* -X1664Y1425D01* -X1664Y1427D01* -X1666Y1427D01* -X1666Y1431D01* -X1668Y1431D01* -X1668Y1433D01* -X1672Y1433D01* -X1672Y1435D01* -X1674Y1435D01* -X1674Y1437D01* -X1678Y1437D01* -X1678Y1439D01* -X1680Y1439D01* -X1680Y1459D01* -X1678Y1459D01* -X1678Y1461D01* -X1674Y1461D01* -X1674Y1463D01* -X1672Y1463D01* -X1672Y1465D01* -X1668Y1465D01* -X1668Y1467D01* -X1666Y1467D01* -X1666Y1471D01* -X1664Y1471D01* -X1664Y1473D01* -X1662Y1473D01* -X1662Y1475D01* -X1660Y1475D01* -X1660Y1479D01* -X1658Y1479D01* -X1658Y1485D01* -X1656Y1485D01* -X1656Y1491D01* -X1654Y1491D01* -X1654Y1507D01* -X1656Y1507D01* -X1656Y1513D01* -X1658Y1513D01* -X1658Y1519D01* -X1660Y1519D01* -X1660Y1523D01* -X1662Y1523D01* -X1662Y1525D01* -X1664Y1525D01* -X1664Y1527D01* -X1666Y1527D01* -X1666Y1531D01* -X1668Y1531D01* -X1668Y1533D01* -X1672Y1533D01* -X1672Y1535D01* -X1674Y1535D01* -X1674Y1555D01* -X1654Y1555D01* -X1654Y1643D01* -X1656Y1643D01* -X1656Y1645D01* -X1622Y1645D01* -G37* -D02* -G36* -X1222Y155D02* -X1222Y153D01* -X2178Y153D01* -X2178Y155D01* -X1222Y155D01* -G37* -D02* -G36* -X1222Y155D02* -X1222Y153D01* -X2178Y153D01* -X2178Y155D01* -X1222Y155D01* -G37* -D02* -G36* -X1222Y153D02* -X1222Y149D01* -X1500Y149D01* -X1500Y147D01* -X1512Y147D01* -X1512Y145D01* -X1518Y145D01* -X1518Y143D01* -X1522Y143D01* -X1522Y141D01* -X1526Y141D01* -X1526Y139D01* -X1528Y139D01* -X1528Y137D01* -X1532Y137D01* -X1532Y135D01* -X1534Y135D01* -X1534Y133D01* -X1536Y133D01* -X1536Y129D01* -X1538Y129D01* -X1538Y127D01* -X1540Y127D01* -X1540Y125D01* -X1542Y125D01* -X1542Y121D01* -X2130Y121D01* -X2130Y123D01* -X2178Y123D01* -X2178Y153D01* -X1222Y153D01* -G37* -D02* -G36* -X1222Y149D02* -X1222Y141D01* -X1226Y141D01* -X1226Y139D01* -X1228Y139D01* -X1228Y137D01* -X1232Y137D01* -X1232Y135D01* -X1234Y135D01* -X1234Y133D01* -X1236Y133D01* -X1236Y129D01* -X1238Y129D01* -X1238Y127D01* -X1260Y127D01* -X1260Y129D01* -X1262Y129D01* -X1262Y131D01* -X1264Y131D01* -X1264Y133D01* -X1266Y133D01* -X1266Y135D01* -X1268Y135D01* -X1268Y137D01* -X1270Y137D01* -X1270Y139D01* -X1272Y139D01* -X1272Y141D01* -X1276Y141D01* -X1276Y143D01* -X1280Y143D01* -X1280Y145D01* -X1286Y145D01* -X1286Y147D01* -X1298Y147D01* -X1298Y149D01* -X1222Y149D01* -G37* -D02* -G36* -X1300Y149D02* -X1300Y147D01* -X1312Y147D01* -X1312Y145D01* -X1318Y145D01* -X1318Y143D01* -X1322Y143D01* -X1322Y141D01* -X1326Y141D01* -X1326Y139D01* -X1328Y139D01* -X1328Y137D01* -X1332Y137D01* -X1332Y135D01* -X1334Y135D01* -X1334Y133D01* -X1336Y133D01* -X1336Y129D01* -X1338Y129D01* -X1338Y127D01* -X1360Y127D01* -X1360Y129D01* -X1362Y129D01* -X1362Y131D01* -X1364Y131D01* -X1364Y133D01* -X1366Y133D01* -X1366Y135D01* -X1368Y135D01* -X1368Y137D01* -X1370Y137D01* -X1370Y139D01* -X1372Y139D01* -X1372Y141D01* -X1376Y141D01* -X1376Y143D01* -X1380Y143D01* -X1380Y145D01* -X1386Y145D01* -X1386Y147D01* -X1398Y147D01* -X1398Y149D01* -X1300Y149D01* -G37* -D02* -G36* -X1400Y149D02* -X1400Y147D01* -X1412Y147D01* -X1412Y145D01* -X1418Y145D01* -X1418Y143D01* -X1422Y143D01* -X1422Y141D01* -X1426Y141D01* -X1426Y139D01* -X1428Y139D01* -X1428Y137D01* -X1432Y137D01* -X1432Y135D01* -X1434Y135D01* -X1434Y133D01* -X1436Y133D01* -X1436Y129D01* -X1438Y129D01* -X1438Y127D01* -X1460Y127D01* -X1460Y129D01* -X1462Y129D01* -X1462Y131D01* -X1464Y131D01* -X1464Y133D01* -X1466Y133D01* -X1466Y135D01* -X1468Y135D01* -X1468Y137D01* -X1470Y137D01* -X1470Y139D01* -X1472Y139D01* -X1472Y141D01* -X1476Y141D01* -X1476Y143D01* -X1480Y143D01* -X1480Y145D01* -X1486Y145D01* -X1486Y147D01* -X1498Y147D01* -X1498Y149D01* -X1400Y149D01* -G37* -D02* -G36* -X132Y1759D02* -X132Y1739D01* -X136Y1739D01* -X136Y1737D01* -X138Y1737D01* -X138Y1735D01* -X140Y1735D01* -X140Y1731D01* -X142Y1731D01* -X142Y1729D01* -X144Y1729D01* -X144Y1725D01* -X146Y1725D01* -X146Y1721D01* -X148Y1721D01* -X148Y1717D01* -X150Y1717D01* -X150Y1711D01* -X152Y1711D01* -X152Y1687D01* -X150Y1687D01* -X150Y1681D01* -X148Y1681D01* -X148Y1677D01* -X146Y1677D01* -X146Y1673D01* -X144Y1673D01* -X144Y1669D01* -X142Y1669D01* -X142Y1667D01* -X140Y1667D01* -X140Y1663D01* -X138Y1663D01* -X138Y1661D01* -X136Y1661D01* -X136Y1659D01* -X132Y1659D01* -X132Y1657D01* -X130Y1657D01* -X130Y1655D01* -X128Y1655D01* -X128Y1653D01* -X124Y1653D01* -X124Y1651D01* -X120Y1651D01* -X120Y1649D01* -X114Y1649D01* -X114Y1647D01* -X104Y1647D01* -X104Y1645D01* -X272Y1645D01* -X272Y1659D01* -X270Y1659D01* -X270Y1661D01* -X268Y1661D01* -X268Y1663D01* -X266Y1663D01* -X266Y1665D01* -X264Y1665D01* -X264Y1667D01* -X262Y1667D01* -X262Y1669D01* -X260Y1669D01* -X260Y1671D01* -X258Y1671D01* -X258Y1675D01* -X256Y1675D01* -X256Y1679D01* -X254Y1679D01* -X254Y1683D01* -X252Y1683D01* -X252Y1691D01* -X250Y1691D01* -X250Y1707D01* -X252Y1707D01* -X252Y1715D01* -X254Y1715D01* -X254Y1719D01* -X256Y1719D01* -X256Y1723D01* -X258Y1723D01* -X258Y1727D01* -X260Y1727D01* -X260Y1729D01* -X262Y1729D01* -X262Y1731D01* -X264Y1731D01* -X264Y1733D01* -X266Y1733D01* -X266Y1735D01* -X268Y1735D01* -X268Y1737D01* -X270Y1737D01* -X270Y1739D01* -X272Y1739D01* -X272Y1759D01* -X132Y1759D01* -G37* -D02* -G36* -X326Y1759D02* -X326Y1739D01* -X328Y1739D01* -X328Y1737D01* -X332Y1737D01* -X332Y1735D01* -X334Y1735D01* -X334Y1733D01* -X336Y1733D01* -X336Y1729D01* -X338Y1729D01* -X338Y1727D01* -X340Y1727D01* -X340Y1725D01* -X342Y1725D01* -X342Y1721D01* -X344Y1721D01* -X344Y1717D01* -X346Y1717D01* -X346Y1709D01* -X348Y1709D01* -X348Y1689D01* -X346Y1689D01* -X346Y1681D01* -X344Y1681D01* -X344Y1677D01* -X342Y1677D01* -X342Y1673D01* -X340Y1673D01* -X340Y1671D01* -X338Y1671D01* -X338Y1669D01* -X336Y1669D01* -X336Y1665D01* -X334Y1665D01* -X334Y1663D01* -X330Y1663D01* -X330Y1661D01* -X328Y1661D01* -X328Y1659D01* -X326Y1659D01* -X326Y1639D01* -X328Y1639D01* -X328Y1637D01* -X332Y1637D01* -X332Y1635D01* -X334Y1635D01* -X334Y1633D01* -X336Y1633D01* -X336Y1629D01* -X338Y1629D01* -X338Y1627D01* -X340Y1627D01* -X340Y1625D01* -X342Y1625D01* -X342Y1621D01* -X344Y1621D01* -X344Y1617D01* -X346Y1617D01* -X346Y1609D01* -X348Y1609D01* -X348Y1589D01* -X346Y1589D01* -X346Y1581D01* -X344Y1581D01* -X344Y1577D01* -X342Y1577D01* -X342Y1573D01* -X340Y1573D01* -X340Y1571D01* -X338Y1571D01* -X338Y1569D01* -X336Y1569D01* -X336Y1565D01* -X334Y1565D01* -X334Y1563D01* -X330Y1563D01* -X330Y1561D01* -X328Y1561D01* -X328Y1559D01* -X326Y1559D01* -X326Y1557D01* -X322Y1557D01* -X322Y1555D01* -X318Y1555D01* -X318Y1553D01* -X312Y1553D01* -X312Y1551D01* -X986Y1551D01* -X986Y1553D01* -X980Y1553D01* -X980Y1555D01* -X976Y1555D01* -X976Y1557D01* -X972Y1557D01* -X972Y1559D01* -X970Y1559D01* -X970Y1561D01* -X968Y1561D01* -X968Y1563D01* -X966Y1563D01* -X966Y1565D01* -X964Y1565D01* -X964Y1567D01* -X962Y1567D01* -X962Y1569D01* -X960Y1569D01* -X960Y1571D01* -X958Y1571D01* -X958Y1575D01* -X956Y1575D01* -X956Y1579D01* -X954Y1579D01* -X954Y1583D01* -X952Y1583D01* -X952Y1591D01* -X950Y1591D01* -X950Y1607D01* -X952Y1607D01* -X952Y1615D01* -X954Y1615D01* -X954Y1619D01* -X956Y1619D01* -X956Y1623D01* -X958Y1623D01* -X958Y1627D01* -X960Y1627D01* -X960Y1629D01* -X962Y1629D01* -X962Y1631D01* -X964Y1631D01* -X964Y1633D01* -X966Y1633D01* -X966Y1635D01* -X968Y1635D01* -X968Y1637D01* -X970Y1637D01* -X970Y1639D01* -X972Y1639D01* -X972Y1659D01* -X970Y1659D01* -X970Y1661D01* -X968Y1661D01* -X968Y1663D01* -X966Y1663D01* -X966Y1665D01* -X964Y1665D01* -X964Y1667D01* -X962Y1667D01* -X962Y1669D01* -X960Y1669D01* -X960Y1671D01* -X958Y1671D01* -X958Y1675D01* -X956Y1675D01* -X956Y1679D01* -X954Y1679D01* -X954Y1683D01* -X952Y1683D01* -X952Y1691D01* -X950Y1691D01* -X950Y1707D01* -X952Y1707D01* -X952Y1715D01* -X954Y1715D01* -X954Y1719D01* -X956Y1719D01* -X956Y1723D01* -X958Y1723D01* -X958Y1727D01* -X960Y1727D01* -X960Y1729D01* -X962Y1729D01* -X962Y1731D01* -X964Y1731D01* -X964Y1733D01* -X966Y1733D01* -X966Y1735D01* -X968Y1735D01* -X968Y1737D01* -X970Y1737D01* -X970Y1739D01* -X972Y1739D01* -X972Y1759D01* -X326Y1759D01* -G37* -D02* -G36* -X1026Y1759D02* -X1026Y1739D01* -X1028Y1739D01* -X1028Y1737D01* -X1032Y1737D01* -X1032Y1735D01* -X1034Y1735D01* -X1034Y1733D01* -X1036Y1733D01* -X1036Y1729D01* -X1038Y1729D01* -X1038Y1727D01* -X1040Y1727D01* -X1040Y1725D01* -X1042Y1725D01* -X1042Y1721D01* -X1044Y1721D01* -X1044Y1717D01* -X1046Y1717D01* -X1046Y1709D01* -X1048Y1709D01* -X1048Y1689D01* -X1046Y1689D01* -X1046Y1681D01* -X1044Y1681D01* -X1044Y1677D01* -X1042Y1677D01* -X1042Y1673D01* -X1040Y1673D01* -X1040Y1671D01* -X1038Y1671D01* -X1038Y1669D01* -X1036Y1669D01* -X1036Y1665D01* -X1034Y1665D01* -X1034Y1663D01* -X1030Y1663D01* -X1030Y1661D01* -X1028Y1661D01* -X1028Y1659D01* -X1026Y1659D01* -X1026Y1651D01* -X1186Y1651D01* -X1186Y1653D01* -X1180Y1653D01* -X1180Y1655D01* -X1176Y1655D01* -X1176Y1657D01* -X1172Y1657D01* -X1172Y1659D01* -X1170Y1659D01* -X1170Y1661D01* -X1168Y1661D01* -X1168Y1663D01* -X1166Y1663D01* -X1166Y1665D01* -X1164Y1665D01* -X1164Y1667D01* -X1162Y1667D01* -X1162Y1669D01* -X1160Y1669D01* -X1160Y1671D01* -X1158Y1671D01* -X1158Y1675D01* -X1156Y1675D01* -X1156Y1679D01* -X1154Y1679D01* -X1154Y1683D01* -X1152Y1683D01* -X1152Y1691D01* -X1150Y1691D01* -X1150Y1707D01* -X1152Y1707D01* -X1152Y1715D01* -X1154Y1715D01* -X1154Y1719D01* -X1156Y1719D01* -X1156Y1723D01* -X1158Y1723D01* -X1158Y1727D01* -X1160Y1727D01* -X1160Y1729D01* -X1162Y1729D01* -X1162Y1731D01* -X1164Y1731D01* -X1164Y1733D01* -X1166Y1733D01* -X1166Y1735D01* -X1168Y1735D01* -X1168Y1737D01* -X1170Y1737D01* -X1170Y1739D01* -X1172Y1739D01* -X1172Y1759D01* -X1026Y1759D01* -G37* -D02* -G36* -X1526Y1759D02* -X1526Y1739D01* -X1528Y1739D01* -X1528Y1737D01* -X1532Y1737D01* -X1532Y1735D01* -X1534Y1735D01* -X1534Y1733D01* -X1536Y1733D01* -X1536Y1729D01* -X1538Y1729D01* -X1538Y1727D01* -X1540Y1727D01* -X1540Y1725D01* -X1542Y1725D01* -X1542Y1721D01* -X1544Y1721D01* -X1544Y1719D01* -X2208Y1719D01* -X2208Y1717D01* -X2212Y1717D01* -X2212Y1715D01* -X2214Y1715D01* -X2214Y1713D01* -X2216Y1713D01* -X2216Y1711D01* -X2218Y1711D01* -X2218Y1709D01* -X2220Y1709D01* -X2220Y1703D01* -X2222Y1703D01* -X2222Y1521D01* -X2260Y1521D01* -X2260Y1523D01* -X2262Y1523D01* -X2262Y1525D01* -X2264Y1525D01* -X2264Y1527D01* -X2266Y1527D01* -X2266Y1531D01* -X2268Y1531D01* -X2268Y1533D01* -X2272Y1533D01* -X2272Y1535D01* -X2274Y1535D01* -X2274Y1537D01* -X2278Y1537D01* -X2278Y1539D01* -X2280Y1539D01* -X2280Y1559D01* -X2278Y1559D01* -X2278Y1561D01* -X2274Y1561D01* -X2274Y1563D01* -X2272Y1563D01* -X2272Y1565D01* -X2268Y1565D01* -X2268Y1567D01* -X2266Y1567D01* -X2266Y1571D01* -X2264Y1571D01* -X2264Y1573D01* -X2262Y1573D01* -X2262Y1575D01* -X2260Y1575D01* -X2260Y1579D01* -X2258Y1579D01* -X2258Y1585D01* -X2256Y1585D01* -X2256Y1591D01* -X2254Y1591D01* -X2254Y1607D01* -X2256Y1607D01* -X2256Y1613D01* -X2258Y1613D01* -X2258Y1619D01* -X2260Y1619D01* -X2260Y1623D01* -X2262Y1623D01* -X2262Y1625D01* -X2264Y1625D01* -X2264Y1627D01* -X2266Y1627D01* -X2266Y1631D01* -X2268Y1631D01* -X2268Y1633D01* -X2272Y1633D01* -X2272Y1635D01* -X2274Y1635D01* -X2274Y1637D01* -X2278Y1637D01* -X2278Y1639D01* -X2280Y1639D01* -X2280Y1641D01* -X2286Y1641D01* -X2286Y1643D01* -X2298Y1643D01* -X2298Y1645D01* -X2494Y1645D01* -X2494Y1647D01* -X2484Y1647D01* -X2484Y1649D01* -X2478Y1649D01* -X2478Y1651D01* -X2476Y1651D01* -X2476Y1653D01* -X2472Y1653D01* -X2472Y1655D01* -X2468Y1655D01* -X2468Y1657D01* -X2466Y1657D01* -X2466Y1659D01* -X2464Y1659D01* -X2464Y1661D01* -X2462Y1661D01* -X2462Y1663D01* -X2460Y1663D01* -X2460Y1665D01* -X2458Y1665D01* -X2458Y1667D01* -X2456Y1667D01* -X2456Y1669D01* -X2454Y1669D01* -X2454Y1673D01* -X2452Y1673D01* -X2452Y1677D01* -X2450Y1677D01* -X2450Y1681D01* -X2448Y1681D01* -X2448Y1689D01* -X2446Y1689D01* -X2446Y1709D01* -X2448Y1709D01* -X2448Y1717D01* -X2450Y1717D01* -X2450Y1721D01* -X2452Y1721D01* -X2452Y1725D01* -X2454Y1725D01* -X2454Y1729D01* -X2456Y1729D01* -X2456Y1731D01* -X2458Y1731D01* -X2458Y1733D01* -X2460Y1733D01* -X2460Y1737D01* -X2464Y1737D01* -X2464Y1739D01* -X2466Y1739D01* -X2466Y1759D01* -X1526Y1759D01* -G37* -D02* -G36* -X1544Y1719D02* -X1544Y1717D01* -X1546Y1717D01* -X1546Y1709D01* -X1548Y1709D01* -X1548Y1689D01* -X1546Y1689D01* -X1546Y1681D01* -X1544Y1681D01* -X1544Y1677D01* -X1542Y1677D01* -X1542Y1673D01* -X1540Y1673D01* -X1540Y1671D01* -X1538Y1671D01* -X1538Y1669D01* -X1536Y1669D01* -X1536Y1665D01* -X1534Y1665D01* -X1534Y1663D01* -X1530Y1663D01* -X1530Y1661D01* -X1528Y1661D01* -X1528Y1659D01* -X1526Y1659D01* -X1526Y1657D01* -X1522Y1657D01* -X1522Y1655D01* -X1518Y1655D01* -X1518Y1653D01* -X1512Y1653D01* -X1512Y1651D01* -X1578Y1651D01* -X1578Y1707D01* -X1580Y1707D01* -X1580Y1709D01* -X1582Y1709D01* -X1582Y1713D01* -X1584Y1713D01* -X1584Y1715D01* -X1588Y1715D01* -X1588Y1717D01* -X1592Y1717D01* -X1592Y1719D01* -X1544Y1719D01* -G37* -D02* -G36* -X1238Y1671D02* -X1238Y1669D01* -X1236Y1669D01* -X1236Y1665D01* -X1234Y1665D01* -X1234Y1663D01* -X1230Y1663D01* -X1230Y1661D01* -X1228Y1661D01* -X1228Y1659D01* -X1226Y1659D01* -X1226Y1657D01* -X1222Y1657D01* -X1222Y1655D01* -X1218Y1655D01* -X1218Y1653D01* -X1212Y1653D01* -X1212Y1651D01* -X1286Y1651D01* -X1286Y1653D01* -X1280Y1653D01* -X1280Y1655D01* -X1276Y1655D01* -X1276Y1657D01* -X1272Y1657D01* -X1272Y1659D01* -X1270Y1659D01* -X1270Y1661D01* -X1268Y1661D01* -X1268Y1663D01* -X1266Y1663D01* -X1266Y1665D01* -X1264Y1665D01* -X1264Y1667D01* -X1262Y1667D01* -X1262Y1669D01* -X1260Y1669D01* -X1260Y1671D01* -X1238Y1671D01* -G37* -D02* -G36* -X1338Y1671D02* -X1338Y1669D01* -X1336Y1669D01* -X1336Y1665D01* -X1334Y1665D01* -X1334Y1663D01* -X1330Y1663D01* -X1330Y1661D01* -X1328Y1661D01* -X1328Y1659D01* -X1326Y1659D01* -X1326Y1657D01* -X1322Y1657D01* -X1322Y1655D01* -X1318Y1655D01* -X1318Y1653D01* -X1312Y1653D01* -X1312Y1651D01* -X1386Y1651D01* -X1386Y1653D01* -X1380Y1653D01* -X1380Y1655D01* -X1376Y1655D01* -X1376Y1657D01* -X1372Y1657D01* -X1372Y1659D01* -X1370Y1659D01* -X1370Y1661D01* -X1368Y1661D01* -X1368Y1663D01* -X1366Y1663D01* -X1366Y1665D01* -X1364Y1665D01* -X1364Y1667D01* -X1362Y1667D01* -X1362Y1669D01* -X1360Y1669D01* -X1360Y1671D01* -X1338Y1671D01* -G37* -D02* -G36* -X1438Y1671D02* -X1438Y1669D01* -X1436Y1669D01* -X1436Y1665D01* -X1434Y1665D01* -X1434Y1663D01* -X1430Y1663D01* -X1430Y1661D01* -X1428Y1661D01* -X1428Y1659D01* -X1426Y1659D01* -X1426Y1657D01* -X1422Y1657D01* -X1422Y1655D01* -X1418Y1655D01* -X1418Y1653D01* -X1412Y1653D01* -X1412Y1651D01* -X1486Y1651D01* -X1486Y1653D01* -X1480Y1653D01* -X1480Y1655D01* -X1476Y1655D01* -X1476Y1657D01* -X1472Y1657D01* -X1472Y1659D01* -X1470Y1659D01* -X1470Y1661D01* -X1468Y1661D01* -X1468Y1663D01* -X1466Y1663D01* -X1466Y1665D01* -X1464Y1665D01* -X1464Y1667D01* -X1462Y1667D01* -X1462Y1669D01* -X1460Y1669D01* -X1460Y1671D01* -X1438Y1671D01* -G37* -D02* -G36* -X2542Y1669D02* -X2542Y1667D01* -X2540Y1667D01* -X2540Y1663D01* -X2538Y1663D01* -X2538Y1661D01* -X2536Y1661D01* -X2536Y1659D01* -X2532Y1659D01* -X2532Y1657D01* -X2530Y1657D01* -X2530Y1655D01* -X2528Y1655D01* -X2528Y1653D01* -X2524Y1653D01* -X2524Y1651D01* -X2520Y1651D01* -X2520Y1649D01* -X2514Y1649D01* -X2514Y1647D01* -X2504Y1647D01* -X2504Y1645D01* -X2562Y1645D01* -X2562Y1669D01* -X2542Y1669D01* -G37* -D02* -G36* -X40Y1665D02* -X40Y1645D01* -X94Y1645D01* -X94Y1647D01* -X84Y1647D01* -X84Y1649D01* -X78Y1649D01* -X78Y1651D01* -X76Y1651D01* -X76Y1653D01* -X72Y1653D01* -X72Y1655D01* -X68Y1655D01* -X68Y1657D01* -X66Y1657D01* -X66Y1659D01* -X64Y1659D01* -X64Y1661D01* -X62Y1661D01* -X62Y1663D01* -X60Y1663D01* -X60Y1665D01* -X40Y1665D01* -G37* -D02* -G36* -X1026Y1651D02* -X1026Y1649D01* -X1578Y1649D01* -X1578Y1651D01* -X1026Y1651D01* -G37* -D02* -G36* -X1026Y1651D02* -X1026Y1649D01* -X1578Y1649D01* -X1578Y1651D01* -X1026Y1651D01* -G37* -D02* -G36* -X1026Y1651D02* -X1026Y1649D01* -X1578Y1649D01* -X1578Y1651D01* -X1026Y1651D01* -G37* -D02* -G36* -X1026Y1651D02* -X1026Y1649D01* -X1578Y1649D01* -X1578Y1651D01* -X1026Y1651D01* -G37* -D02* -G36* -X1026Y1651D02* -X1026Y1649D01* -X1578Y1649D01* -X1578Y1651D01* -X1026Y1651D01* -G37* -D02* -G36* -X1026Y1649D02* -X1026Y1639D01* -X1028Y1639D01* -X1028Y1637D01* -X1032Y1637D01* -X1032Y1635D01* -X1034Y1635D01* -X1034Y1633D01* -X1036Y1633D01* -X1036Y1629D01* -X1038Y1629D01* -X1038Y1627D01* -X1040Y1627D01* -X1040Y1625D01* -X1042Y1625D01* -X1042Y1621D01* -X1044Y1621D01* -X1044Y1617D01* -X1046Y1617D01* -X1046Y1609D01* -X1048Y1609D01* -X1048Y1589D01* -X1046Y1589D01* -X1046Y1581D01* -X1044Y1581D01* -X1044Y1577D01* -X1042Y1577D01* -X1042Y1573D01* -X1040Y1573D01* -X1040Y1571D01* -X1038Y1571D01* -X1038Y1569D01* -X1036Y1569D01* -X1036Y1565D01* -X1034Y1565D01* -X1034Y1563D01* -X1030Y1563D01* -X1030Y1561D01* -X1028Y1561D01* -X1028Y1559D01* -X1026Y1559D01* -X1026Y1557D01* -X1022Y1557D01* -X1022Y1555D01* -X1018Y1555D01* -X1018Y1553D01* -X1012Y1553D01* -X1012Y1551D01* -X1578Y1551D01* -X1578Y1649D01* -X1026Y1649D01* -G37* -D02* -G36* -X40Y1645D02* -X40Y1643D01* -X272Y1643D01* -X272Y1645D01* -X40Y1645D01* -G37* -D02* -G36* -X40Y1645D02* -X40Y1643D01* -X272Y1643D01* -X272Y1645D01* -X40Y1645D01* -G37* -D02* -G36* -X2300Y1645D02* -X2300Y1643D01* -X2562Y1643D01* -X2562Y1645D01* -X2300Y1645D01* -G37* -D02* -G36* -X2300Y1645D02* -X2300Y1643D01* -X2562Y1643D01* -X2562Y1645D01* -X2300Y1645D01* -G37* -D02* -G36* -X40Y1643D02* -X40Y1551D01* -X286Y1551D01* -X286Y1553D01* -X280Y1553D01* -X280Y1555D01* -X276Y1555D01* -X276Y1557D01* -X272Y1557D01* -X272Y1559D01* -X270Y1559D01* -X270Y1561D01* -X268Y1561D01* -X268Y1563D01* -X266Y1563D01* -X266Y1565D01* -X264Y1565D01* -X264Y1567D01* -X262Y1567D01* -X262Y1569D01* -X260Y1569D01* -X260Y1571D01* -X258Y1571D01* -X258Y1575D01* -X256Y1575D01* -X256Y1579D01* -X254Y1579D01* -X254Y1583D01* -X252Y1583D01* -X252Y1591D01* -X250Y1591D01* -X250Y1607D01* -X252Y1607D01* -X252Y1615D01* -X254Y1615D01* -X254Y1619D01* -X256Y1619D01* -X256Y1623D01* -X258Y1623D01* -X258Y1627D01* -X260Y1627D01* -X260Y1629D01* -X262Y1629D01* -X262Y1631D01* -X264Y1631D01* -X264Y1633D01* -X266Y1633D01* -X266Y1635D01* -X268Y1635D01* -X268Y1637D01* -X270Y1637D01* -X270Y1639D01* -X272Y1639D01* -X272Y1643D01* -X40Y1643D01* -G37* -D02* -G36* -X2312Y1643D02* -X2312Y1641D01* -X2318Y1641D01* -X2318Y1639D01* -X2322Y1639D01* -X2322Y1637D01* -X2324Y1637D01* -X2324Y1635D01* -X2328Y1635D01* -X2328Y1633D01* -X2330Y1633D01* -X2330Y1631D01* -X2332Y1631D01* -X2332Y1629D01* -X2334Y1629D01* -X2334Y1627D01* -X2336Y1627D01* -X2336Y1623D01* -X2338Y1623D01* -X2338Y1619D01* -X2340Y1619D01* -X2340Y1615D01* -X2342Y1615D01* -X2342Y1609D01* -X2344Y1609D01* -X2344Y1589D01* -X2342Y1589D01* -X2342Y1583D01* -X2340Y1583D01* -X2340Y1579D01* -X2338Y1579D01* -X2338Y1575D01* -X2336Y1575D01* -X2336Y1573D01* -X2334Y1573D01* -X2334Y1569D01* -X2332Y1569D01* -X2332Y1567D01* -X2330Y1567D01* -X2330Y1565D01* -X2328Y1565D01* -X2328Y1563D01* -X2324Y1563D01* -X2324Y1561D01* -X2322Y1561D01* -X2322Y1559D01* -X2318Y1559D01* -X2318Y1539D01* -X2322Y1539D01* -X2322Y1537D01* -X2324Y1537D01* -X2324Y1535D01* -X2328Y1535D01* -X2328Y1533D01* -X2330Y1533D01* -X2330Y1531D01* -X2332Y1531D01* -X2332Y1529D01* -X2334Y1529D01* -X2334Y1527D01* -X2336Y1527D01* -X2336Y1523D01* -X2338Y1523D01* -X2338Y1519D01* -X2340Y1519D01* -X2340Y1515D01* -X2342Y1515D01* -X2342Y1509D01* -X2344Y1509D01* -X2344Y1489D01* -X2342Y1489D01* -X2342Y1483D01* -X2340Y1483D01* -X2340Y1479D01* -X2338Y1479D01* -X2338Y1475D01* -X2336Y1475D01* -X2336Y1473D01* -X2334Y1473D01* -X2334Y1469D01* -X2332Y1469D01* -X2332Y1467D01* -X2330Y1467D01* -X2330Y1465D01* -X2328Y1465D01* -X2328Y1463D01* -X2324Y1463D01* -X2324Y1461D01* -X2322Y1461D01* -X2322Y1459D01* -X2318Y1459D01* -X2318Y1439D01* -X2322Y1439D01* -X2322Y1437D01* -X2324Y1437D01* -X2324Y1435D01* -X2328Y1435D01* -X2328Y1433D01* -X2330Y1433D01* -X2330Y1431D01* -X2332Y1431D01* -X2332Y1429D01* -X2334Y1429D01* -X2334Y1427D01* -X2336Y1427D01* -X2336Y1423D01* -X2338Y1423D01* -X2338Y1419D01* -X2340Y1419D01* -X2340Y1415D01* -X2342Y1415D01* -X2342Y1409D01* -X2344Y1409D01* -X2344Y1389D01* -X2342Y1389D01* -X2342Y1383D01* -X2340Y1383D01* -X2340Y1379D01* -X2338Y1379D01* -X2338Y1375D01* -X2336Y1375D01* -X2336Y1373D01* -X2334Y1373D01* -X2334Y1369D01* -X2332Y1369D01* -X2332Y1367D01* -X2330Y1367D01* -X2330Y1365D01* -X2328Y1365D01* -X2328Y1363D01* -X2324Y1363D01* -X2324Y1361D01* -X2322Y1361D01* -X2322Y1359D01* -X2318Y1359D01* -X2318Y1339D01* -X2322Y1339D01* -X2322Y1337D01* -X2324Y1337D01* -X2324Y1335D01* -X2328Y1335D01* -X2328Y1333D01* -X2330Y1333D01* -X2330Y1331D01* -X2332Y1331D01* -X2332Y1329D01* -X2334Y1329D01* -X2334Y1327D01* -X2336Y1327D01* -X2336Y1323D01* -X2338Y1323D01* -X2338Y1319D01* -X2340Y1319D01* -X2340Y1315D01* -X2342Y1315D01* -X2342Y1309D01* -X2344Y1309D01* -X2344Y1289D01* -X2342Y1289D01* -X2342Y1283D01* -X2340Y1283D01* -X2340Y1279D01* -X2338Y1279D01* -X2338Y1275D01* -X2336Y1275D01* -X2336Y1273D01* -X2334Y1273D01* -X2334Y1269D01* -X2332Y1269D01* -X2332Y1267D01* -X2330Y1267D01* -X2330Y1265D01* -X2328Y1265D01* -X2328Y1263D01* -X2324Y1263D01* -X2324Y1261D01* -X2322Y1261D01* -X2322Y1259D01* -X2318Y1259D01* -X2318Y1239D01* -X2322Y1239D01* -X2322Y1237D01* -X2324Y1237D01* -X2324Y1235D01* -X2328Y1235D01* -X2328Y1233D01* -X2330Y1233D01* -X2330Y1231D01* -X2332Y1231D01* -X2332Y1229D01* -X2334Y1229D01* -X2334Y1227D01* -X2336Y1227D01* -X2336Y1223D01* -X2338Y1223D01* -X2338Y1219D01* -X2340Y1219D01* -X2340Y1215D01* -X2342Y1215D01* -X2342Y1209D01* -X2344Y1209D01* -X2344Y1189D01* -X2342Y1189D01* -X2342Y1183D01* -X2340Y1183D01* -X2340Y1179D01* -X2338Y1179D01* -X2338Y1175D01* -X2336Y1175D01* -X2336Y1173D01* -X2334Y1173D01* -X2334Y1169D01* -X2332Y1169D01* -X2332Y1167D01* -X2330Y1167D01* -X2330Y1165D01* -X2328Y1165D01* -X2328Y1163D01* -X2324Y1163D01* -X2324Y1161D01* -X2322Y1161D01* -X2322Y1159D01* -X2318Y1159D01* -X2318Y1139D01* -X2322Y1139D01* -X2322Y1137D01* -X2324Y1137D01* -X2324Y1135D01* -X2328Y1135D01* -X2328Y1133D01* -X2330Y1133D01* -X2330Y1131D01* -X2332Y1131D01* -X2332Y1129D01* -X2334Y1129D01* -X2334Y1127D01* -X2336Y1127D01* -X2336Y1123D01* -X2338Y1123D01* -X2338Y1119D01* -X2340Y1119D01* -X2340Y1115D01* -X2342Y1115D01* -X2342Y1109D01* -X2344Y1109D01* -X2344Y1089D01* -X2342Y1089D01* -X2342Y1083D01* -X2340Y1083D01* -X2340Y1079D01* -X2338Y1079D01* -X2338Y1075D01* -X2336Y1075D01* -X2336Y1073D01* -X2334Y1073D01* -X2334Y1069D01* -X2332Y1069D01* -X2332Y1067D01* -X2330Y1067D01* -X2330Y1065D01* -X2328Y1065D01* -X2328Y1063D01* -X2324Y1063D01* -X2324Y1061D01* -X2322Y1061D01* -X2322Y1059D01* -X2318Y1059D01* -X2318Y1039D01* -X2322Y1039D01* -X2322Y1037D01* -X2324Y1037D01* -X2324Y1035D01* -X2328Y1035D01* -X2328Y1033D01* -X2330Y1033D01* -X2330Y1031D01* -X2332Y1031D01* -X2332Y1029D01* -X2334Y1029D01* -X2334Y1027D01* -X2336Y1027D01* -X2336Y1023D01* -X2338Y1023D01* -X2338Y1019D01* -X2340Y1019D01* -X2340Y1015D01* -X2342Y1015D01* -X2342Y1009D01* -X2344Y1009D01* -X2344Y989D01* -X2342Y989D01* -X2342Y983D01* -X2340Y983D01* -X2340Y979D01* -X2338Y979D01* -X2338Y975D01* -X2336Y975D01* -X2336Y973D01* -X2334Y973D01* -X2334Y969D01* -X2332Y969D01* -X2332Y967D01* -X2330Y967D01* -X2330Y965D01* -X2328Y965D01* -X2328Y963D01* -X2324Y963D01* -X2324Y961D01* -X2322Y961D01* -X2322Y959D01* -X2318Y959D01* -X2318Y939D01* -X2322Y939D01* -X2322Y937D01* -X2324Y937D01* -X2324Y935D01* -X2328Y935D01* -X2328Y933D01* -X2330Y933D01* -X2330Y931D01* -X2332Y931D01* -X2332Y929D01* -X2334Y929D01* -X2334Y927D01* -X2336Y927D01* -X2336Y923D01* -X2338Y923D01* -X2338Y919D01* -X2340Y919D01* -X2340Y915D01* -X2342Y915D01* -X2342Y909D01* -X2344Y909D01* -X2344Y889D01* -X2342Y889D01* -X2342Y883D01* -X2340Y883D01* -X2340Y879D01* -X2338Y879D01* -X2338Y875D01* -X2336Y875D01* -X2336Y873D01* -X2334Y873D01* -X2334Y869D01* -X2332Y869D01* -X2332Y867D01* -X2330Y867D01* -X2330Y865D01* -X2328Y865D01* -X2328Y863D01* -X2324Y863D01* -X2324Y861D01* -X2322Y861D01* -X2322Y859D01* -X2318Y859D01* -X2318Y839D01* -X2322Y839D01* -X2322Y837D01* -X2324Y837D01* -X2324Y835D01* -X2328Y835D01* -X2328Y833D01* -X2330Y833D01* -X2330Y831D01* -X2332Y831D01* -X2332Y829D01* -X2334Y829D01* -X2334Y827D01* -X2336Y827D01* -X2336Y823D01* -X2338Y823D01* -X2338Y819D01* -X2340Y819D01* -X2340Y815D01* -X2342Y815D01* -X2342Y809D01* -X2344Y809D01* -X2344Y789D01* -X2342Y789D01* -X2342Y783D01* -X2340Y783D01* -X2340Y779D01* -X2338Y779D01* -X2338Y775D01* -X2336Y775D01* -X2336Y773D01* -X2334Y773D01* -X2334Y769D01* -X2332Y769D01* -X2332Y767D01* -X2330Y767D01* -X2330Y765D01* -X2328Y765D01* -X2328Y763D01* -X2324Y763D01* -X2324Y761D01* -X2322Y761D01* -X2322Y759D01* -X2318Y759D01* -X2318Y739D01* -X2322Y739D01* -X2322Y737D01* -X2324Y737D01* -X2324Y735D01* -X2328Y735D01* -X2328Y733D01* -X2330Y733D01* -X2330Y731D01* -X2332Y731D01* -X2332Y729D01* -X2334Y729D01* -X2334Y727D01* -X2336Y727D01* -X2336Y723D01* -X2338Y723D01* -X2338Y719D01* -X2340Y719D01* -X2340Y715D01* -X2342Y715D01* -X2342Y709D01* -X2344Y709D01* -X2344Y689D01* -X2342Y689D01* -X2342Y683D01* -X2340Y683D01* -X2340Y679D01* -X2338Y679D01* -X2338Y675D01* -X2336Y675D01* -X2336Y673D01* -X2334Y673D01* -X2334Y669D01* -X2332Y669D01* -X2332Y667D01* -X2330Y667D01* -X2330Y665D01* -X2328Y665D01* -X2328Y663D01* -X2324Y663D01* -X2324Y661D01* -X2322Y661D01* -X2322Y659D01* -X2318Y659D01* -X2318Y639D01* -X2322Y639D01* -X2322Y637D01* -X2324Y637D01* -X2324Y635D01* -X2328Y635D01* -X2328Y633D01* -X2330Y633D01* -X2330Y631D01* -X2332Y631D01* -X2332Y629D01* -X2334Y629D01* -X2334Y627D01* -X2336Y627D01* -X2336Y623D01* -X2338Y623D01* -X2338Y619D01* -X2340Y619D01* -X2340Y615D01* -X2342Y615D01* -X2342Y609D01* -X2344Y609D01* -X2344Y589D01* -X2342Y589D01* -X2342Y583D01* -X2340Y583D01* -X2340Y579D01* -X2338Y579D01* -X2338Y575D01* -X2336Y575D01* -X2336Y573D01* -X2334Y573D01* -X2334Y569D01* -X2332Y569D01* -X2332Y567D01* -X2330Y567D01* -X2330Y565D01* -X2328Y565D01* -X2328Y563D01* -X2324Y563D01* -X2324Y561D01* -X2322Y561D01* -X2322Y559D01* -X2318Y559D01* -X2318Y539D01* -X2322Y539D01* -X2322Y537D01* -X2324Y537D01* -X2324Y535D01* -X2328Y535D01* -X2328Y533D01* -X2330Y533D01* -X2330Y531D01* -X2332Y531D01* -X2332Y529D01* -X2334Y529D01* -X2334Y527D01* -X2336Y527D01* -X2336Y523D01* -X2338Y523D01* -X2338Y519D01* -X2340Y519D01* -X2340Y515D01* -X2342Y515D01* -X2342Y509D01* -X2344Y509D01* -X2344Y489D01* -X2342Y489D01* -X2342Y483D01* -X2340Y483D01* -X2340Y479D01* -X2338Y479D01* -X2338Y475D01* -X2336Y475D01* -X2336Y473D01* -X2334Y473D01* -X2334Y469D01* -X2332Y469D01* -X2332Y467D01* -X2330Y467D01* -X2330Y465D01* -X2328Y465D01* -X2328Y463D01* -X2324Y463D01* -X2324Y461D01* -X2322Y461D01* -X2322Y459D01* -X2318Y459D01* -X2318Y439D01* -X2322Y439D01* -X2322Y437D01* -X2324Y437D01* -X2324Y435D01* -X2328Y435D01* -X2328Y433D01* -X2330Y433D01* -X2330Y431D01* -X2332Y431D01* -X2332Y429D01* -X2334Y429D01* -X2334Y427D01* -X2336Y427D01* -X2336Y423D01* -X2338Y423D01* -X2338Y419D01* -X2340Y419D01* -X2340Y415D01* -X2342Y415D01* -X2342Y409D01* -X2344Y409D01* -X2344Y389D01* -X2342Y389D01* -X2342Y383D01* -X2340Y383D01* -X2340Y379D01* -X2338Y379D01* -X2338Y375D01* -X2336Y375D01* -X2336Y373D01* -X2334Y373D01* -X2334Y369D01* -X2332Y369D01* -X2332Y367D01* -X2330Y367D01* -X2330Y365D01* -X2328Y365D01* -X2328Y363D01* -X2324Y363D01* -X2324Y361D01* -X2322Y361D01* -X2322Y359D01* -X2318Y359D01* -X2318Y339D01* -X2322Y339D01* -X2322Y337D01* -X2324Y337D01* -X2324Y335D01* -X2328Y335D01* -X2328Y333D01* -X2330Y333D01* -X2330Y331D01* -X2332Y331D01* -X2332Y329D01* -X2334Y329D01* -X2334Y327D01* -X2336Y327D01* -X2336Y323D01* -X2338Y323D01* -X2338Y319D01* -X2340Y319D01* -X2340Y315D01* -X2342Y315D01* -X2342Y309D01* -X2344Y309D01* -X2344Y289D01* -X2342Y289D01* -X2342Y283D01* -X2340Y283D01* -X2340Y279D01* -X2338Y279D01* -X2338Y275D01* -X2336Y275D01* -X2336Y273D01* -X2334Y273D01* -X2334Y269D01* -X2332Y269D01* -X2332Y267D01* -X2330Y267D01* -X2330Y265D01* -X2328Y265D01* -X2328Y263D01* -X2324Y263D01* -X2324Y261D01* -X2322Y261D01* -X2322Y259D01* -X2318Y259D01* -X2318Y239D01* -X2322Y239D01* -X2322Y237D01* -X2324Y237D01* -X2324Y235D01* -X2328Y235D01* -X2328Y233D01* -X2330Y233D01* -X2330Y231D01* -X2332Y231D01* -X2332Y229D01* -X2334Y229D01* -X2334Y227D01* -X2336Y227D01* -X2336Y223D01* -X2338Y223D01* -X2338Y219D01* -X2340Y219D01* -X2340Y215D01* -X2342Y215D01* -X2342Y209D01* -X2344Y209D01* -X2344Y189D01* -X2342Y189D01* -X2342Y183D01* -X2340Y183D01* -X2340Y179D01* -X2338Y179D01* -X2338Y175D01* -X2336Y175D01* -X2336Y173D01* -X2334Y173D01* -X2334Y169D01* -X2332Y169D01* -X2332Y167D01* -X2330Y167D01* -X2330Y165D01* -X2328Y165D01* -X2328Y163D01* -X2324Y163D01* -X2324Y161D01* -X2322Y161D01* -X2322Y159D01* -X2318Y159D01* -X2318Y157D01* -X2312Y157D01* -X2312Y155D01* -X2562Y155D01* -X2562Y1643D01* -X2312Y1643D01* -G37* -D02* -G36* -X40Y1551D02* -X40Y1549D01* -X1578Y1549D01* -X1578Y1551D01* -X40Y1551D01* -G37* -D02* -G36* -X40Y1551D02* -X40Y1549D01* -X1578Y1549D01* -X1578Y1551D01* -X40Y1551D01* -G37* -D02* -G36* -X40Y1551D02* -X40Y1549D01* -X1578Y1549D01* -X1578Y1551D01* -X40Y1551D01* -G37* -D02* -G36* -X40Y1549D02* -X40Y1149D01* -X900Y1149D01* -X900Y1147D01* -X912Y1147D01* -X912Y1145D01* -X918Y1145D01* -X918Y1143D01* -X922Y1143D01* -X922Y1141D01* -X926Y1141D01* -X926Y1139D01* -X928Y1139D01* -X928Y1137D01* -X932Y1137D01* -X932Y1135D01* -X934Y1135D01* -X934Y1133D01* -X936Y1133D01* -X936Y1129D01* -X938Y1129D01* -X938Y1127D01* -X940Y1127D01* -X940Y1125D01* -X942Y1125D01* -X942Y1121D01* -X944Y1121D01* -X944Y1117D01* -X946Y1117D01* -X946Y1109D01* -X948Y1109D01* -X948Y1089D01* -X946Y1089D01* -X946Y1081D01* -X944Y1081D01* -X944Y1077D01* -X942Y1077D01* -X942Y1073D01* -X940Y1073D01* -X940Y1071D01* -X938Y1071D01* -X938Y1069D01* -X936Y1069D01* -X936Y1065D01* -X934Y1065D01* -X934Y1063D01* -X930Y1063D01* -X930Y1061D01* -X928Y1061D01* -X928Y1059D01* -X926Y1059D01* -X926Y1057D01* -X922Y1057D01* -X922Y1055D01* -X918Y1055D01* -X918Y1053D01* -X912Y1053D01* -X912Y1051D01* -X1578Y1051D01* -X1578Y1549D01* -X40Y1549D01* -G37* -D02* -G36* -X2222Y1277D02* -X2222Y155D01* -X2288Y155D01* -X2288Y157D01* -X2282Y157D01* -X2282Y159D01* -X2278Y159D01* -X2278Y161D01* -X2274Y161D01* -X2274Y163D01* -X2272Y163D01* -X2272Y165D01* -X2268Y165D01* -X2268Y167D01* -X2266Y167D01* -X2266Y171D01* -X2264Y171D01* -X2264Y173D01* -X2262Y173D01* -X2262Y175D01* -X2260Y175D01* -X2260Y179D01* -X2258Y179D01* -X2258Y185D01* -X2256Y185D01* -X2256Y191D01* -X2254Y191D01* -X2254Y207D01* -X2256Y207D01* -X2256Y213D01* -X2258Y213D01* -X2258Y219D01* -X2260Y219D01* -X2260Y223D01* -X2262Y223D01* -X2262Y225D01* -X2264Y225D01* -X2264Y227D01* -X2266Y227D01* -X2266Y231D01* -X2268Y231D01* -X2268Y233D01* -X2272Y233D01* -X2272Y235D01* -X2274Y235D01* -X2274Y237D01* -X2278Y237D01* -X2278Y239D01* -X2280Y239D01* -X2280Y259D01* -X2278Y259D01* -X2278Y261D01* -X2274Y261D01* -X2274Y263D01* -X2272Y263D01* -X2272Y265D01* -X2268Y265D01* -X2268Y267D01* -X2266Y267D01* -X2266Y271D01* -X2264Y271D01* -X2264Y273D01* -X2262Y273D01* -X2262Y275D01* -X2260Y275D01* -X2260Y279D01* -X2258Y279D01* -X2258Y285D01* -X2256Y285D01* -X2256Y291D01* -X2254Y291D01* -X2254Y307D01* -X2256Y307D01* -X2256Y313D01* -X2258Y313D01* -X2258Y319D01* -X2260Y319D01* -X2260Y323D01* -X2262Y323D01* -X2262Y325D01* -X2264Y325D01* -X2264Y327D01* -X2266Y327D01* -X2266Y331D01* -X2268Y331D01* -X2268Y333D01* -X2272Y333D01* -X2272Y335D01* -X2274Y335D01* -X2274Y337D01* -X2278Y337D01* -X2278Y339D01* -X2280Y339D01* -X2280Y359D01* -X2278Y359D01* -X2278Y361D01* -X2274Y361D01* -X2274Y363D01* -X2272Y363D01* -X2272Y365D01* -X2268Y365D01* -X2268Y367D01* -X2266Y367D01* -X2266Y371D01* -X2264Y371D01* -X2264Y373D01* -X2262Y373D01* -X2262Y375D01* -X2260Y375D01* -X2260Y379D01* -X2258Y379D01* -X2258Y385D01* -X2256Y385D01* -X2256Y391D01* -X2254Y391D01* -X2254Y407D01* -X2256Y407D01* -X2256Y413D01* -X2258Y413D01* -X2258Y419D01* -X2260Y419D01* -X2260Y423D01* -X2262Y423D01* -X2262Y425D01* -X2264Y425D01* -X2264Y427D01* -X2266Y427D01* -X2266Y431D01* -X2268Y431D01* -X2268Y433D01* -X2272Y433D01* -X2272Y435D01* -X2274Y435D01* -X2274Y437D01* -X2278Y437D01* -X2278Y439D01* -X2280Y439D01* -X2280Y459D01* -X2278Y459D01* -X2278Y461D01* -X2274Y461D01* -X2274Y463D01* -X2272Y463D01* -X2272Y465D01* -X2268Y465D01* -X2268Y467D01* -X2266Y467D01* -X2266Y471D01* -X2264Y471D01* -X2264Y473D01* -X2262Y473D01* -X2262Y475D01* -X2260Y475D01* -X2260Y479D01* -X2258Y479D01* -X2258Y485D01* -X2256Y485D01* -X2256Y491D01* -X2254Y491D01* -X2254Y507D01* -X2256Y507D01* -X2256Y513D01* -X2258Y513D01* -X2258Y519D01* -X2260Y519D01* -X2260Y523D01* -X2262Y523D01* -X2262Y525D01* -X2264Y525D01* -X2264Y527D01* -X2266Y527D01* -X2266Y531D01* -X2268Y531D01* -X2268Y533D01* -X2272Y533D01* -X2272Y535D01* -X2274Y535D01* -X2274Y537D01* -X2278Y537D01* -X2278Y539D01* -X2280Y539D01* -X2280Y559D01* -X2278Y559D01* -X2278Y561D01* -X2274Y561D01* -X2274Y563D01* -X2272Y563D01* -X2272Y565D01* -X2268Y565D01* -X2268Y567D01* -X2266Y567D01* -X2266Y571D01* -X2264Y571D01* -X2264Y573D01* -X2262Y573D01* -X2262Y575D01* -X2260Y575D01* -X2260Y579D01* -X2258Y579D01* -X2258Y585D01* -X2256Y585D01* -X2256Y591D01* -X2254Y591D01* -X2254Y607D01* -X2256Y607D01* -X2256Y613D01* -X2258Y613D01* -X2258Y619D01* -X2260Y619D01* -X2260Y623D01* -X2262Y623D01* -X2262Y625D01* -X2264Y625D01* -X2264Y627D01* -X2266Y627D01* -X2266Y631D01* -X2268Y631D01* -X2268Y633D01* -X2272Y633D01* -X2272Y635D01* -X2274Y635D01* -X2274Y637D01* -X2278Y637D01* -X2278Y639D01* -X2280Y639D01* -X2280Y659D01* -X2278Y659D01* -X2278Y661D01* -X2274Y661D01* -X2274Y663D01* -X2272Y663D01* -X2272Y665D01* -X2268Y665D01* -X2268Y667D01* -X2266Y667D01* -X2266Y671D01* -X2264Y671D01* -X2264Y673D01* -X2262Y673D01* -X2262Y675D01* -X2260Y675D01* -X2260Y679D01* -X2258Y679D01* -X2258Y685D01* -X2256Y685D01* -X2256Y691D01* -X2254Y691D01* -X2254Y707D01* -X2256Y707D01* -X2256Y713D01* -X2258Y713D01* -X2258Y719D01* -X2260Y719D01* -X2260Y723D01* -X2262Y723D01* -X2262Y725D01* -X2264Y725D01* -X2264Y727D01* -X2266Y727D01* -X2266Y731D01* -X2268Y731D01* -X2268Y733D01* -X2272Y733D01* -X2272Y735D01* -X2274Y735D01* -X2274Y737D01* -X2278Y737D01* -X2278Y739D01* -X2280Y739D01* -X2280Y759D01* -X2278Y759D01* -X2278Y761D01* -X2274Y761D01* -X2274Y763D01* -X2272Y763D01* -X2272Y765D01* -X2268Y765D01* -X2268Y767D01* -X2266Y767D01* -X2266Y771D01* -X2264Y771D01* -X2264Y773D01* -X2262Y773D01* -X2262Y775D01* -X2260Y775D01* -X2260Y779D01* -X2258Y779D01* -X2258Y785D01* -X2256Y785D01* -X2256Y791D01* -X2254Y791D01* -X2254Y807D01* -X2256Y807D01* -X2256Y813D01* -X2258Y813D01* -X2258Y819D01* -X2260Y819D01* -X2260Y823D01* -X2262Y823D01* -X2262Y825D01* -X2264Y825D01* -X2264Y827D01* -X2266Y827D01* -X2266Y831D01* -X2268Y831D01* -X2268Y833D01* -X2272Y833D01* -X2272Y835D01* -X2274Y835D01* -X2274Y837D01* -X2278Y837D01* -X2278Y839D01* -X2280Y839D01* -X2280Y859D01* -X2278Y859D01* -X2278Y861D01* -X2274Y861D01* -X2274Y863D01* -X2272Y863D01* -X2272Y865D01* -X2268Y865D01* -X2268Y867D01* -X2266Y867D01* -X2266Y871D01* -X2264Y871D01* -X2264Y873D01* -X2262Y873D01* -X2262Y875D01* -X2260Y875D01* -X2260Y879D01* -X2258Y879D01* -X2258Y885D01* -X2256Y885D01* -X2256Y891D01* -X2254Y891D01* -X2254Y907D01* -X2256Y907D01* -X2256Y913D01* -X2258Y913D01* -X2258Y919D01* -X2260Y919D01* -X2260Y923D01* -X2262Y923D01* -X2262Y925D01* -X2264Y925D01* -X2264Y927D01* -X2266Y927D01* -X2266Y931D01* -X2268Y931D01* -X2268Y933D01* -X2272Y933D01* -X2272Y935D01* -X2274Y935D01* -X2274Y937D01* -X2278Y937D01* -X2278Y939D01* -X2280Y939D01* -X2280Y959D01* -X2278Y959D01* -X2278Y961D01* -X2274Y961D01* -X2274Y963D01* -X2272Y963D01* -X2272Y965D01* -X2268Y965D01* -X2268Y967D01* -X2266Y967D01* -X2266Y971D01* -X2264Y971D01* -X2264Y973D01* -X2262Y973D01* -X2262Y975D01* -X2260Y975D01* -X2260Y979D01* -X2258Y979D01* -X2258Y985D01* -X2256Y985D01* -X2256Y991D01* -X2254Y991D01* -X2254Y1007D01* -X2256Y1007D01* -X2256Y1013D01* -X2258Y1013D01* -X2258Y1019D01* -X2260Y1019D01* -X2260Y1023D01* -X2262Y1023D01* -X2262Y1025D01* -X2264Y1025D01* -X2264Y1027D01* -X2266Y1027D01* -X2266Y1031D01* -X2268Y1031D01* -X2268Y1033D01* -X2272Y1033D01* -X2272Y1035D01* -X2274Y1035D01* -X2274Y1037D01* -X2278Y1037D01* -X2278Y1039D01* -X2280Y1039D01* -X2280Y1059D01* -X2278Y1059D01* -X2278Y1061D01* -X2274Y1061D01* -X2274Y1063D01* -X2272Y1063D01* -X2272Y1065D01* -X2268Y1065D01* -X2268Y1067D01* -X2266Y1067D01* -X2266Y1071D01* -X2264Y1071D01* -X2264Y1073D01* -X2262Y1073D01* -X2262Y1075D01* -X2260Y1075D01* -X2260Y1079D01* -X2258Y1079D01* -X2258Y1085D01* -X2256Y1085D01* -X2256Y1091D01* -X2254Y1091D01* -X2254Y1107D01* -X2256Y1107D01* -X2256Y1113D01* -X2258Y1113D01* -X2258Y1119D01* -X2260Y1119D01* -X2260Y1123D01* -X2262Y1123D01* -X2262Y1125D01* -X2264Y1125D01* -X2264Y1127D01* -X2266Y1127D01* -X2266Y1131D01* -X2268Y1131D01* -X2268Y1133D01* -X2272Y1133D01* -X2272Y1135D01* -X2274Y1135D01* -X2274Y1137D01* -X2278Y1137D01* -X2278Y1139D01* -X2280Y1139D01* -X2280Y1159D01* -X2278Y1159D01* -X2278Y1161D01* -X2274Y1161D01* -X2274Y1163D01* -X2272Y1163D01* -X2272Y1165D01* -X2268Y1165D01* -X2268Y1167D01* -X2266Y1167D01* -X2266Y1171D01* -X2264Y1171D01* -X2264Y1173D01* -X2262Y1173D01* -X2262Y1175D01* -X2260Y1175D01* -X2260Y1179D01* -X2258Y1179D01* -X2258Y1185D01* -X2256Y1185D01* -X2256Y1191D01* -X2254Y1191D01* -X2254Y1207D01* -X2256Y1207D01* -X2256Y1213D01* -X2258Y1213D01* -X2258Y1219D01* -X2260Y1219D01* -X2260Y1223D01* -X2262Y1223D01* -X2262Y1225D01* -X2264Y1225D01* -X2264Y1227D01* -X2266Y1227D01* -X2266Y1231D01* -X2268Y1231D01* -X2268Y1233D01* -X2272Y1233D01* -X2272Y1235D01* -X2274Y1235D01* -X2274Y1237D01* -X2278Y1237D01* -X2278Y1239D01* -X2280Y1239D01* -X2280Y1259D01* -X2278Y1259D01* -X2278Y1261D01* -X2274Y1261D01* -X2274Y1263D01* -X2272Y1263D01* -X2272Y1265D01* -X2268Y1265D01* -X2268Y1267D01* -X2266Y1267D01* -X2266Y1271D01* -X2264Y1271D01* -X2264Y1273D01* -X2262Y1273D01* -X2262Y1275D01* -X2260Y1275D01* -X2260Y1277D01* -X2222Y1277D01* -G37* -D02* -G36* -X40Y1149D02* -X40Y1051D01* -X386Y1051D01* -X386Y1053D01* -X380Y1053D01* -X380Y1055D01* -X376Y1055D01* -X376Y1057D01* -X372Y1057D01* -X372Y1059D01* -X370Y1059D01* -X370Y1061D01* -X368Y1061D01* -X368Y1063D01* -X366Y1063D01* -X366Y1065D01* -X364Y1065D01* -X364Y1067D01* -X362Y1067D01* -X362Y1069D01* -X360Y1069D01* -X360Y1071D01* -X358Y1071D01* -X358Y1075D01* -X356Y1075D01* -X356Y1079D01* -X354Y1079D01* -X354Y1083D01* -X352Y1083D01* -X352Y1091D01* -X350Y1091D01* -X350Y1107D01* -X352Y1107D01* -X352Y1115D01* -X354Y1115D01* -X354Y1119D01* -X356Y1119D01* -X356Y1123D01* -X358Y1123D01* -X358Y1127D01* -X360Y1127D01* -X360Y1129D01* -X362Y1129D01* -X362Y1131D01* -X364Y1131D01* -X364Y1133D01* -X366Y1133D01* -X366Y1135D01* -X368Y1135D01* -X368Y1137D01* -X370Y1137D01* -X370Y1139D01* -X372Y1139D01* -X372Y1141D01* -X376Y1141D01* -X376Y1143D01* -X380Y1143D01* -X380Y1145D01* -X386Y1145D01* -X386Y1147D01* -X398Y1147D01* -X398Y1149D01* -X40Y1149D01* -G37* -D02* -G36* -X400Y1149D02* -X400Y1147D01* -X412Y1147D01* -X412Y1145D01* -X418Y1145D01* -X418Y1143D01* -X422Y1143D01* -X422Y1141D01* -X426Y1141D01* -X426Y1139D01* -X428Y1139D01* -X428Y1137D01* -X432Y1137D01* -X432Y1135D01* -X434Y1135D01* -X434Y1133D01* -X436Y1133D01* -X436Y1129D01* -X438Y1129D01* -X438Y1127D01* -X460Y1127D01* -X460Y1129D01* -X462Y1129D01* -X462Y1131D01* -X464Y1131D01* -X464Y1133D01* -X466Y1133D01* -X466Y1135D01* -X468Y1135D01* -X468Y1137D01* -X470Y1137D01* -X470Y1139D01* -X472Y1139D01* -X472Y1141D01* -X476Y1141D01* -X476Y1143D01* -X480Y1143D01* -X480Y1145D01* -X486Y1145D01* -X486Y1147D01* -X498Y1147D01* -X498Y1149D01* -X400Y1149D01* -G37* -D02* -G36* -X500Y1149D02* -X500Y1147D01* -X512Y1147D01* -X512Y1145D01* -X518Y1145D01* -X518Y1143D01* -X522Y1143D01* -X522Y1141D01* -X526Y1141D01* -X526Y1139D01* -X528Y1139D01* -X528Y1137D01* -X532Y1137D01* -X532Y1135D01* -X534Y1135D01* -X534Y1133D01* -X536Y1133D01* -X536Y1129D01* -X538Y1129D01* -X538Y1127D01* -X560Y1127D01* -X560Y1129D01* -X562Y1129D01* -X562Y1131D01* -X564Y1131D01* -X564Y1133D01* -X566Y1133D01* -X566Y1135D01* -X568Y1135D01* -X568Y1137D01* -X570Y1137D01* -X570Y1139D01* -X572Y1139D01* -X572Y1141D01* -X576Y1141D01* -X576Y1143D01* -X580Y1143D01* -X580Y1145D01* -X586Y1145D01* -X586Y1147D01* -X598Y1147D01* -X598Y1149D01* -X500Y1149D01* -G37* -D02* -G36* -X600Y1149D02* -X600Y1147D01* -X612Y1147D01* -X612Y1145D01* -X618Y1145D01* -X618Y1143D01* -X622Y1143D01* -X622Y1141D01* -X626Y1141D01* -X626Y1139D01* -X628Y1139D01* -X628Y1137D01* -X632Y1137D01* -X632Y1135D01* -X634Y1135D01* -X634Y1133D01* -X636Y1133D01* -X636Y1129D01* -X638Y1129D01* -X638Y1127D01* -X660Y1127D01* -X660Y1129D01* -X662Y1129D01* -X662Y1131D01* -X664Y1131D01* -X664Y1133D01* -X666Y1133D01* -X666Y1135D01* -X668Y1135D01* -X668Y1137D01* -X670Y1137D01* -X670Y1139D01* -X672Y1139D01* -X672Y1141D01* -X676Y1141D01* -X676Y1143D01* -X680Y1143D01* -X680Y1145D01* -X686Y1145D01* -X686Y1147D01* -X698Y1147D01* -X698Y1149D01* -X600Y1149D01* -G37* -D02* -G36* -X700Y1149D02* -X700Y1147D01* -X712Y1147D01* -X712Y1145D01* -X718Y1145D01* -X718Y1143D01* -X722Y1143D01* -X722Y1141D01* -X726Y1141D01* -X726Y1139D01* -X728Y1139D01* -X728Y1137D01* -X732Y1137D01* -X732Y1135D01* -X734Y1135D01* -X734Y1133D01* -X736Y1133D01* -X736Y1129D01* -X738Y1129D01* -X738Y1127D01* -X760Y1127D01* -X760Y1129D01* -X762Y1129D01* -X762Y1131D01* -X764Y1131D01* -X764Y1133D01* -X766Y1133D01* -X766Y1135D01* -X768Y1135D01* -X768Y1137D01* -X770Y1137D01* -X770Y1139D01* -X772Y1139D01* -X772Y1141D01* -X776Y1141D01* -X776Y1143D01* -X780Y1143D01* -X780Y1145D01* -X786Y1145D01* -X786Y1147D01* -X798Y1147D01* -X798Y1149D01* -X700Y1149D01* -G37* -D02* -G36* -X800Y1149D02* -X800Y1147D01* -X812Y1147D01* -X812Y1145D01* -X818Y1145D01* -X818Y1143D01* -X822Y1143D01* -X822Y1141D01* -X826Y1141D01* -X826Y1139D01* -X828Y1139D01* -X828Y1137D01* -X832Y1137D01* -X832Y1135D01* -X834Y1135D01* -X834Y1133D01* -X836Y1133D01* -X836Y1129D01* -X838Y1129D01* -X838Y1127D01* -X860Y1127D01* -X860Y1129D01* -X862Y1129D01* -X862Y1131D01* -X864Y1131D01* -X864Y1133D01* -X866Y1133D01* -X866Y1135D01* -X868Y1135D01* -X868Y1137D01* -X870Y1137D01* -X870Y1139D01* -X872Y1139D01* -X872Y1141D01* -X876Y1141D01* -X876Y1143D01* -X880Y1143D01* -X880Y1145D01* -X886Y1145D01* -X886Y1147D01* -X898Y1147D01* -X898Y1149D01* -X800Y1149D01* -G37* -D02* -G36* -X438Y1071D02* -X438Y1069D01* -X436Y1069D01* -X436Y1065D01* -X434Y1065D01* -X434Y1063D01* -X430Y1063D01* -X430Y1061D01* -X428Y1061D01* -X428Y1059D01* -X426Y1059D01* -X426Y1057D01* -X422Y1057D01* -X422Y1055D01* -X418Y1055D01* -X418Y1053D01* -X412Y1053D01* -X412Y1051D01* -X478Y1051D01* -X478Y1055D01* -X476Y1055D01* -X476Y1057D01* -X472Y1057D01* -X472Y1059D01* -X470Y1059D01* -X470Y1061D01* -X468Y1061D01* -X468Y1063D01* -X466Y1063D01* -X466Y1065D01* -X464Y1065D01* -X464Y1067D01* -X462Y1067D01* -X462Y1069D01* -X460Y1069D01* -X460Y1071D01* -X438Y1071D01* -G37* -D02* -G36* -X538Y1071D02* -X538Y1069D01* -X536Y1069D01* -X536Y1065D01* -X534Y1065D01* -X534Y1063D01* -X530Y1063D01* -X530Y1061D01* -X528Y1061D01* -X528Y1059D01* -X526Y1059D01* -X526Y1057D01* -X522Y1057D01* -X522Y1051D01* -X586Y1051D01* -X586Y1053D01* -X580Y1053D01* -X580Y1055D01* -X576Y1055D01* -X576Y1057D01* -X572Y1057D01* -X572Y1059D01* -X570Y1059D01* -X570Y1061D01* -X568Y1061D01* -X568Y1063D01* -X566Y1063D01* -X566Y1065D01* -X564Y1065D01* -X564Y1067D01* -X562Y1067D01* -X562Y1069D01* -X560Y1069D01* -X560Y1071D01* -X538Y1071D01* -G37* -D02* -G36* -X638Y1071D02* -X638Y1069D01* -X636Y1069D01* -X636Y1065D01* -X634Y1065D01* -X634Y1063D01* -X630Y1063D01* -X630Y1061D01* -X628Y1061D01* -X628Y1059D01* -X626Y1059D01* -X626Y1057D01* -X622Y1057D01* -X622Y1055D01* -X618Y1055D01* -X618Y1053D01* -X612Y1053D01* -X612Y1051D01* -X686Y1051D01* -X686Y1053D01* -X680Y1053D01* -X680Y1055D01* -X676Y1055D01* -X676Y1057D01* -X672Y1057D01* -X672Y1059D01* -X670Y1059D01* -X670Y1061D01* -X668Y1061D01* -X668Y1063D01* -X666Y1063D01* -X666Y1065D01* -X664Y1065D01* -X664Y1067D01* -X662Y1067D01* -X662Y1069D01* -X660Y1069D01* -X660Y1071D01* -X638Y1071D01* -G37* -D02* -G36* -X738Y1071D02* -X738Y1069D01* -X736Y1069D01* -X736Y1065D01* -X734Y1065D01* -X734Y1063D01* -X730Y1063D01* -X730Y1061D01* -X728Y1061D01* -X728Y1059D01* -X726Y1059D01* -X726Y1057D01* -X722Y1057D01* -X722Y1055D01* -X718Y1055D01* -X718Y1053D01* -X712Y1053D01* -X712Y1051D01* -X786Y1051D01* -X786Y1053D01* -X780Y1053D01* -X780Y1055D01* -X776Y1055D01* -X776Y1057D01* -X772Y1057D01* -X772Y1059D01* -X770Y1059D01* -X770Y1061D01* -X768Y1061D01* -X768Y1063D01* -X766Y1063D01* -X766Y1065D01* -X764Y1065D01* -X764Y1067D01* -X762Y1067D01* -X762Y1069D01* -X760Y1069D01* -X760Y1071D01* -X738Y1071D01* -G37* -D02* -G36* -X838Y1071D02* -X838Y1069D01* -X836Y1069D01* -X836Y1065D01* -X834Y1065D01* -X834Y1063D01* -X830Y1063D01* -X830Y1061D01* -X828Y1061D01* -X828Y1059D01* -X826Y1059D01* -X826Y1057D01* -X822Y1057D01* -X822Y1055D01* -X818Y1055D01* -X818Y1053D01* -X812Y1053D01* -X812Y1051D01* -X886Y1051D01* -X886Y1053D01* -X880Y1053D01* -X880Y1055D01* -X876Y1055D01* -X876Y1057D01* -X872Y1057D01* -X872Y1059D01* -X870Y1059D01* -X870Y1061D01* -X868Y1061D01* -X868Y1063D01* -X866Y1063D01* -X866Y1065D01* -X864Y1065D01* -X864Y1067D01* -X862Y1067D01* -X862Y1069D01* -X860Y1069D01* -X860Y1071D01* -X838Y1071D01* -G37* -D02* -G36* -X40Y1051D02* -X40Y1049D01* -X478Y1049D01* -X478Y1051D01* -X40Y1051D01* -G37* -D02* -G36* -X40Y1051D02* -X40Y1049D01* -X478Y1049D01* -X478Y1051D01* -X40Y1051D01* -G37* -D02* -G36* -X522Y1051D02* -X522Y1049D01* -X1578Y1049D01* -X1578Y1051D01* -X522Y1051D01* -G37* -D02* -G36* -X522Y1051D02* -X522Y1049D01* -X1578Y1049D01* -X1578Y1051D01* -X522Y1051D01* -G37* -D02* -G36* -X522Y1051D02* -X522Y1049D01* -X1578Y1049D01* -X1578Y1051D01* -X522Y1051D01* -G37* -D02* -G36* -X522Y1051D02* -X522Y1049D01* -X1578Y1049D01* -X1578Y1051D01* -X522Y1051D01* -G37* -D02* -G36* -X522Y1051D02* -X522Y1049D01* -X1578Y1049D01* -X1578Y1051D01* -X522Y1051D01* -G37* -D02* -G36* -X40Y1049D02* -X40Y153D01* -X104Y153D01* -X104Y151D01* -X114Y151D01* -X114Y149D01* -X120Y149D01* -X120Y147D01* -X124Y147D01* -X124Y145D01* -X128Y145D01* -X128Y143D01* -X130Y143D01* -X130Y141D01* -X132Y141D01* -X132Y139D01* -X136Y139D01* -X136Y137D01* -X138Y137D01* -X138Y135D01* -X140Y135D01* -X140Y131D01* -X142Y131D01* -X142Y129D01* -X144Y129D01* -X144Y125D01* -X146Y125D01* -X146Y123D01* -X148Y123D01* -X148Y117D01* -X150Y117D01* -X150Y111D01* -X152Y111D01* -X152Y87D01* -X150Y87D01* -X150Y81D01* -X148Y81D01* -X148Y77D01* -X146Y77D01* -X146Y73D01* -X144Y73D01* -X144Y69D01* -X142Y69D01* -X142Y67D01* -X140Y67D01* -X140Y63D01* -X138Y63D01* -X138Y61D01* -X136Y61D01* -X136Y41D01* -X1170Y41D01* -X1170Y61D01* -X1168Y61D01* -X1168Y63D01* -X1166Y63D01* -X1166Y65D01* -X1164Y65D01* -X1164Y67D01* -X1162Y67D01* -X1162Y69D01* -X1160Y69D01* -X1160Y71D01* -X1158Y71D01* -X1158Y75D01* -X1156Y75D01* -X1156Y77D01* -X562Y77D01* -X562Y79D01* -X492Y79D01* -X492Y81D01* -X488Y81D01* -X488Y83D01* -X484Y83D01* -X484Y87D01* -X482Y87D01* -X482Y89D01* -X480Y89D01* -X480Y93D01* -X478Y93D01* -X478Y1049D01* -X40Y1049D01* -G37* -D02* -G36* -X522Y1049D02* -X522Y123D01* -X570Y123D01* -X570Y121D01* -X1156Y121D01* -X1156Y123D01* -X1158Y123D01* -X1158Y127D01* -X1160Y127D01* -X1160Y129D01* -X1162Y129D01* -X1162Y131D01* -X1164Y131D01* -X1164Y133D01* -X1166Y133D01* -X1166Y135D01* -X1168Y135D01* -X1168Y137D01* -X1170Y137D01* -X1170Y139D01* -X1172Y139D01* -X1172Y141D01* -X1176Y141D01* -X1176Y143D01* -X1178Y143D01* -X1178Y207D01* -X1180Y207D01* -X1180Y211D01* -X1182Y211D01* -X1182Y213D01* -X1184Y213D01* -X1184Y215D01* -X1186Y215D01* -X1186Y217D01* -X1188Y217D01* -X1188Y219D01* -X1194Y219D01* -X1194Y221D01* -X1578Y221D01* -X1578Y1049D01* -X522Y1049D01* -G37* -D02* -G36* -X2222Y155D02* -X2222Y153D01* -X2562Y153D01* -X2562Y155D01* -X2222Y155D01* -G37* -D02* -G36* -X2222Y155D02* -X2222Y153D01* -X2562Y153D01* -X2562Y155D01* -X2222Y155D01* -G37* -D02* -G36* -X40Y153D02* -X40Y133D01* -X60Y133D01* -X60Y137D01* -X64Y137D01* -X64Y139D01* -X66Y139D01* -X66Y141D01* -X68Y141D01* -X68Y143D01* -X72Y143D01* -X72Y145D01* -X74Y145D01* -X74Y147D01* -X78Y147D01* -X78Y149D01* -X84Y149D01* -X84Y151D01* -X94Y151D01* -X94Y153D01* -X40Y153D01* -G37* -D02* -G36* -X2222Y153D02* -X2222Y93D01* -X2220Y93D01* -X2220Y89D01* -X2218Y89D01* -X2218Y87D01* -X2216Y87D01* -X2216Y85D01* -X2214Y85D01* -X2214Y83D01* -X2212Y83D01* -X2212Y81D01* -X2208Y81D01* -X2208Y79D01* -X2138Y79D01* -X2138Y77D01* -X1542Y77D01* -X1542Y73D01* -X1540Y73D01* -X1540Y71D01* -X1538Y71D01* -X1538Y69D01* -X1536Y69D01* -X1536Y65D01* -X1534Y65D01* -X1534Y63D01* -X1530Y63D01* -X1530Y61D01* -X1528Y61D01* -X1528Y41D01* -X2464Y41D01* -X2464Y61D01* -X2462Y61D01* -X2462Y63D01* -X2460Y63D01* -X2460Y65D01* -X2458Y65D01* -X2458Y67D01* -X2456Y67D01* -X2456Y69D01* -X2454Y69D01* -X2454Y73D01* -X2452Y73D01* -X2452Y77D01* -X2450Y77D01* -X2450Y81D01* -X2448Y81D01* -X2448Y89D01* -X2446Y89D01* -X2446Y109D01* -X2448Y109D01* -X2448Y117D01* -X2450Y117D01* -X2450Y121D01* -X2452Y121D01* -X2452Y125D01* -X2454Y125D01* -X2454Y129D01* -X2456Y129D01* -X2456Y131D01* -X2458Y131D01* -X2458Y133D01* -X2460Y133D01* -X2460Y137D01* -X2464Y137D01* -X2464Y139D01* -X2466Y139D01* -X2466Y141D01* -X2468Y141D01* -X2468Y143D01* -X2472Y143D01* -X2472Y145D01* -X2474Y145D01* -X2474Y147D01* -X2478Y147D01* -X2478Y149D01* -X2484Y149D01* -X2484Y151D01* -X2494Y151D01* -X2494Y153D01* -X2222Y153D01* -G37* -D02* -G36* -X2504Y153D02* -X2504Y151D01* -X2514Y151D01* -X2514Y149D01* -X2520Y149D01* -X2520Y147D01* -X2524Y147D01* -X2524Y145D01* -X2528Y145D01* -X2528Y143D01* -X2530Y143D01* -X2530Y141D01* -X2532Y141D01* -X2532Y139D01* -X2536Y139D01* -X2536Y137D01* -X2538Y137D01* -X2538Y135D01* -X2540Y135D01* -X2540Y131D01* -X2542Y131D01* -X2542Y129D01* -X2562Y129D01* -X2562Y153D01* -X2504Y153D01* -G37* -D02* -G04 End of Copper1* -M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_drill.txt b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_drill.txt deleted file mode 100644 index fe270b6..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_drill.txt +++ /dev/null @@ -1,65 +0,0 @@ -; NON-PLATED HOLES START AT T1 -; THROUGH (PLATED) HOLES START AT T100 -M48 -INCH -T1C0.086614 -T100C0.038000 -T101C0.036000 -% -T1 -X024992Y016990 -X000992Y000990 -X024992Y000990 -X000992Y016990 -T100 -X014992Y000990 -X011992Y016990 -X003992Y010990 -X005992Y010990 -X012992Y016990 -X002992Y016990 -X009992Y015990 -X013992Y000990 -X004992Y010990 -X011992Y000990 -X012992Y000990 -X009992Y016990 -X006992Y010990 -X013992Y016990 -X008992Y010990 -X007992Y010990 -X002992Y015990 -X014992Y016990 -T101 -X022992Y009990 -X016992Y015990 -X016992Y011990 -X016992Y001990 -X022992Y013990 -X022992Y015990 -X016992Y005990 -X016992Y008990 -X022992Y010990 -X016992Y009990 -X016992Y006990 -X022992Y001990 -X022992Y002990 -X022992Y006990 -X016992Y003990 -X022992Y012990 -X022992Y014990 -X022992Y004990 -X022992Y003990 -X022992Y011990 -X016992Y007990 -X016992Y010990 -X022992Y005990 -X016992Y002990 -X016992Y004990 -X016992Y013990 -X022992Y007990 -X016992Y014990 -X022992Y008990 -X016992Y012990 -T00 -M30 diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskBottom.gbs b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskBottom.gbs deleted file mode 100644 index 9293e97..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskBottom.gbs +++ /dev/null @@ -1,76 +0,0 @@ -G04 MADE WITH FRITZING* -G04 WWW.FRITZING.ORG* -G04 DOUBLE SIDED* -G04 HOLES PLATED* -G04 CONTOUR ON CENTER OF CONTOUR VECTOR* -%ASAXBY*% -%FSLAX23Y23*% -%MOIN*% -%OFA0B0*% -%SFA1.0B1.0*% -%ADD10C,0.080000*% -%ADD11C,0.088000*% -%ADD12C,0.096614*% -%ADD13R,0.079972X0.080000*% -%LNMASK0*% -G90* -G70* -G54D10* -X1699Y1599D03* -X1699Y1499D03* -X1699Y1399D03* -X1699Y1299D03* -X1699Y1199D03* -X1699Y1099D03* -X1699Y999D03* -X1699Y899D03* -X1699Y799D03* -X1699Y699D03* -X1699Y599D03* -X1699Y499D03* -X1699Y399D03* -X1699Y299D03* -X1699Y199D03* -X2299Y1599D03* -X2299Y1499D03* -X2299Y1399D03* -X2299Y1299D03* -X2299Y1199D03* -X2299Y1099D03* -X2299Y999D03* -X2299Y899D03* -X2299Y799D03* -X2299Y699D03* -X2299Y599D03* -X2299Y499D03* -X2299Y399D03* -X2299Y299D03* -X2299Y199D03* -G54D11* -X1199Y1699D03* -X1299Y1699D03* -X1399Y1699D03* -X1499Y1699D03* -X1199Y99D03* -X1299Y99D03* -X1399Y99D03* -X1499Y99D03* -X399Y1099D03* -X499Y1099D03* -X599Y1099D03* -X699Y1099D03* -X799Y1099D03* -X899Y1099D03* -X299Y1699D03* -X299Y1599D03* -X999Y1699D03* -X999Y1599D03* -G54D12* -X2499Y99D03* -X99Y99D03* -X99Y1699D03* -X2499Y1699D03* -G54D13* -X1699Y1599D03* -G04 End of Mask0* -M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskTop.gts b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskTop.gts deleted file mode 100644 index de20a39..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_maskTop.gts +++ /dev/null @@ -1,76 +0,0 @@ -G04 MADE WITH FRITZING* -G04 WWW.FRITZING.ORG* -G04 DOUBLE SIDED* -G04 HOLES PLATED* -G04 CONTOUR ON CENTER OF CONTOUR VECTOR* -%ASAXBY*% -%FSLAX23Y23*% -%MOIN*% -%OFA0B0*% -%SFA1.0B1.0*% -%ADD10C,0.080000*% -%ADD11C,0.088000*% -%ADD12C,0.096614*% -%ADD13R,0.079972X0.080000*% -%LNMASK1*% -G90* -G70* -G54D10* -X1699Y1599D03* -X1699Y1499D03* -X1699Y1399D03* -X1699Y1299D03* -X1699Y1199D03* -X1699Y1099D03* -X1699Y999D03* -X1699Y899D03* -X1699Y799D03* -X1699Y699D03* -X1699Y599D03* -X1699Y499D03* -X1699Y399D03* -X1699Y299D03* -X1699Y199D03* -X2299Y1599D03* -X2299Y1499D03* -X2299Y1399D03* -X2299Y1299D03* -X2299Y1199D03* -X2299Y1099D03* -X2299Y999D03* -X2299Y899D03* -X2299Y799D03* -X2299Y699D03* -X2299Y599D03* -X2299Y499D03* -X2299Y399D03* -X2299Y299D03* -X2299Y199D03* -G54D11* -X1199Y1699D03* -X1299Y1699D03* -X1399Y1699D03* -X1499Y1699D03* -X1199Y99D03* -X1299Y99D03* -X1399Y99D03* -X1499Y99D03* -X399Y1099D03* -X499Y1099D03* -X599Y1099D03* -X699Y1099D03* -X799Y1099D03* -X899Y1099D03* -X299Y1699D03* -X299Y1599D03* -X999Y1699D03* -X999Y1599D03* -G54D12* -X2499Y99D03* -X99Y99D03* -X99Y1699D03* -X2499Y1699D03* -G54D13* -X1699Y1599D03* -G04 End of Mask1* -M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_pnp.txt b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_pnp.txt deleted file mode 100644 index 8c47f66..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_pnp.txt +++ /dev/null @@ -1,33 +0,0 @@ -*Pick And Place List -*Company= -*Author= -*eMail= -* -*Project=emergency_stop -*Date=14:38:19 -*CreatedBy=Fritzing 0.9.10b.2022-07-01.CD-2134-0-40d23c29 -* -* -*Coordinates in mm, always center of component -*Origin 0/0=Lower left corner of PCB -*Rotation in degree (0-360, math. pos.) -* -*No;Value;Package;X;Y;Rotation;Side;Name -1;;;15.6175;-12.3318;0;Bottom;TXT1 -2;;;50.7814;-22.8277;0;Bottom;�p�[�c1 -3;;;2.52128;-43.1561;0;Bottom;Hole2 -4;;THT;16.4914;-27.9161;-90;Bottom;J1 -5;;;25.3492;-22.7586;0;Bottom;Copper Fill5 -6;;THT;25.3814;-41.8861;0;Bottom;J2 -7;;;63.4813;-2.51621;0;Bottom;Hole4 -8;;;33.0454;-22.8602;0;Bottom;Copper Fill3 -9;;;29.21;-21.4886;0;Bottom;Copper Fill4 -10;;THT;34.2714;-2.51612;-90;Bottom;J5 -11;;THT;7.60137;-41.8861;0;Bottom;J3 -12;;;63.4813;-43.1561;0;Bottom;Hole1 -13;;;39.37;-36.7286;0;Bottom;Copper Fill2 -14;;;33.0454;-22.8602;0;Bottom;Copper Fill7 -15;;THT;34.2714;-43.1561;-90;Bottom;J4 -16;;;2.52128;-2.51621;0;Bottom;Hole3 -17;;;44.4754;-22.8094;0;Bottom;Copper Fill6 -18;;;38.1;-35.4586;0;Bottom;Copper Fill1 diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkBottom.gbo b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkBottom.gbo deleted file mode 100644 index f015c28..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkBottom.gbo +++ /dev/null @@ -1,24 +0,0 @@ -G04 MADE WITH FRITZING* -G04 WWW.FRITZING.ORG* -G04 DOUBLE SIDED* -G04 HOLES PLATED* -G04 CONTOUR ON CENTER OF CONTOUR VECTOR* -%ASAXBY*% -%FSLAX23Y23*% -%MOIN*% -%OFA0B0*% -%SFA1.0B1.0*% -%ADD10R,2.602410X1.799010X2.586410X1.783010*% -%ADD11C,0.008000*% -%LNSILK0*% -G90* -G70* -G54D11* -X4Y1795D02* -X2598Y1795D01* -X2598Y4D01* -X4Y4D01* -X4Y1795D01* -D02* -G04 End of Silk0* -M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkTop.gto b/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkTop.gto deleted file mode 100644 index 5b2ba5c..0000000 --- a/src/zlac8015d_ros/emergency_stop/module_PCB/gerber/emergency_stop_silkTop.gto +++ /dev/null @@ -1,9583 +0,0 @@ -G04 MADE WITH FRITZING* -G04 WWW.FRITZING.ORG* -G04 DOUBLE SIDED* -G04 HOLES PLATED* -G04 CONTOUR ON CENTER OF CONTOUR VECTOR* -%ASAXBY*% -%FSLAX23Y23*% -%MOIN*% -%OFA0B0*% -%SFA1.0B1.0*% -%ADD10C,0.010000*% -%ADD11C,0.005000*% -%ADD12C,0.008000*% -%ADD13R,0.001000X0.001000*% -%LNSILK1*% -G90* -G70* -G54D10* -X1149Y1649D02* -X1549Y1649D01* -D02* -X1549Y1649D02* -X1549Y1749D01* -D02* -X1549Y1749D02* -X1149Y1749D01* -D02* -X1149Y1749D02* -X1149Y1649D01* -D02* -X1149Y49D02* -X1549Y49D01* -D02* -X1549Y49D02* -X1549Y149D01* -D02* -X1549Y149D02* -X1149Y149D01* -D02* -X1149Y149D02* -X1149Y49D01* -D02* -X349Y1049D02* -X949Y1049D01* -D02* -X949Y1049D02* -X949Y1149D01* -D02* -X949Y1149D02* -X349Y1149D01* -D02* -X349Y1149D02* -X349Y1049D01* -G54D11* -D02* -X384Y1049D02* -X349Y1084D01* -G54D10* -D02* -X249Y1749D02* -X249Y1549D01* -D02* -X249Y1549D02* -X349Y1549D01* -D02* -X349Y1549D02* -X349Y1749D01* -D02* -X349Y1749D02* -X249Y1749D01* -D02* -X949Y1749D02* -X949Y1549D01* -D02* -X949Y1549D02* -X1049Y1549D01* -D02* -X1049Y1549D02* -X1049Y1749D01* -D02* -X1049Y1749D02* -X949Y1749D01* -G54D12* -X1653Y53D02* -X2345Y53D01* -X2345Y1745D01* -X1653Y1745D01* -X1653Y53D01* -D02* -G54D13* -X1Y1799D02* -X2602Y1799D01* -X1Y1798D02* -X2602Y1798D01* -X1Y1797D02* -X2602Y1797D01* -X1Y1796D02* -X2602Y1796D01* -X1Y1795D02* -X2602Y1795D01* -X1Y1794D02* -X2602Y1794D01* -X1Y1793D02* -X2602Y1793D01* -X1Y1792D02* -X2602Y1792D01* -X1Y1791D02* -X8Y1791D01* -X2595Y1791D02* -X2602Y1791D01* -X1Y1790D02* -X8Y1790D01* -X2595Y1790D02* -X2602Y1790D01* -X1Y1789D02* -X8Y1789D01* -X2595Y1789D02* -X2602Y1789D01* -X1Y1788D02* -X8Y1788D01* -X2595Y1788D02* -X2602Y1788D01* -X1Y1787D02* -X8Y1787D01* -X2595Y1787D02* -X2602Y1787D01* -X1Y1786D02* -X8Y1786D01* -X2595Y1786D02* -X2602Y1786D01* -X1Y1785D02* -X8Y1785D01* -X2595Y1785D02* -X2602Y1785D01* -X1Y1784D02* -X8Y1784D01* -X2595Y1784D02* -X2602Y1784D01* -X1Y1783D02* -X8Y1783D01* -X2595Y1783D02* -X2602Y1783D01* -X1Y1782D02* -X8Y1782D01* -X2595Y1782D02* -X2602Y1782D01* -X1Y1781D02* -X8Y1781D01* -X2595Y1781D02* -X2602Y1781D01* -X1Y1780D02* -X8Y1780D01* -X2595Y1780D02* -X2602Y1780D01* -X1Y1779D02* -X8Y1779D01* -X2595Y1779D02* -X2602Y1779D01* -X1Y1778D02* -X8Y1778D01* -X2595Y1778D02* -X2602Y1778D01* -X1Y1777D02* -X8Y1777D01* -X2595Y1777D02* -X2602Y1777D01* -X1Y1776D02* -X8Y1776D01* -X2595Y1776D02* -X2602Y1776D01* -X1Y1775D02* -X8Y1775D01* -X2595Y1775D02* -X2602Y1775D01* -X1Y1774D02* -X8Y1774D01* -X2595Y1774D02* -X2602Y1774D01* -X1Y1773D02* -X8Y1773D01* -X2595Y1773D02* -X2602Y1773D01* -X1Y1772D02* -X8Y1772D01* -X2595Y1772D02* -X2602Y1772D01* -X1Y1771D02* -X8Y1771D01* -X2595Y1771D02* -X2602Y1771D01* -X1Y1770D02* -X8Y1770D01* -X2595Y1770D02* -X2602Y1770D01* -X1Y1769D02* -X8Y1769D01* -X2595Y1769D02* -X2602Y1769D01* -X1Y1768D02* -X8Y1768D01* -X2595Y1768D02* -X2602Y1768D01* -X1Y1767D02* -X8Y1767D01* -X2595Y1767D02* -X2602Y1767D01* -X1Y1766D02* -X8Y1766D01* -X2595Y1766D02* -X2602Y1766D01* -X1Y1765D02* -X8Y1765D01* -X2595Y1765D02* -X2602Y1765D01* -X1Y1764D02* -X8Y1764D01* -X2595Y1764D02* -X2602Y1764D01* -X1Y1763D02* -X8Y1763D01* -X2595Y1763D02* -X2602Y1763D01* -X1Y1762D02* -X8Y1762D01* -X2595Y1762D02* -X2602Y1762D01* -X1Y1761D02* -X8Y1761D01* -X2595Y1761D02* -X2602Y1761D01* -X1Y1760D02* -X8Y1760D01* -X2595Y1760D02* -X2602Y1760D01* -X1Y1759D02* -X8Y1759D01* -X2595Y1759D02* -X2602Y1759D01* -X1Y1758D02* -X8Y1758D01* -X2595Y1758D02* -X2602Y1758D01* -X1Y1757D02* -X8Y1757D01* -X2595Y1757D02* -X2602Y1757D01* -X1Y1756D02* -X8Y1756D01* -X2595Y1756D02* -X2602Y1756D01* -X1Y1755D02* -X8Y1755D01* -X2595Y1755D02* -X2602Y1755D01* -X1Y1754D02* -X8Y1754D01* -X2595Y1754D02* -X2602Y1754D01* -X1Y1753D02* -X8Y1753D01* -X2595Y1753D02* -X2602Y1753D01* -X1Y1752D02* -X8Y1752D01* -X2595Y1752D02* -X2602Y1752D01* -X1Y1751D02* -X8Y1751D01* -X283Y1751D02* -X283Y1751D01* -X983Y1751D02* -X983Y1751D01* -X2595Y1751D02* -X2602Y1751D01* -X1Y1750D02* -X8Y1750D01* -X282Y1750D02* -X284Y1750D01* -X982Y1750D02* -X984Y1750D01* -X2595Y1750D02* -X2602Y1750D01* -X1Y1749D02* -X8Y1749D01* -X281Y1749D02* -X285Y1749D01* -X981Y1749D02* -X985Y1749D01* -X2595Y1749D02* -X2602Y1749D01* -X1Y1748D02* -X8Y1748D01* -X280Y1748D02* -X286Y1748D01* -X980Y1748D02* -X986Y1748D01* -X2595Y1748D02* -X2602Y1748D01* -X1Y1747D02* -X8Y1747D01* -X279Y1747D02* -X285Y1747D01* -X979Y1747D02* -X985Y1747D01* -X2595Y1747D02* -X2602Y1747D01* -X1Y1746D02* -X8Y1746D01* -X278Y1746D02* -X284Y1746D01* -X978Y1746D02* -X984Y1746D01* -X2595Y1746D02* -X2602Y1746D01* -X1Y1745D02* -X8Y1745D01* -X277Y1745D02* -X283Y1745D01* -X977Y1745D02* -X983Y1745D01* -X2595Y1745D02* -X2602Y1745D01* -X1Y1744D02* -X8Y1744D01* -X276Y1744D02* -X282Y1744D01* -X976Y1744D02* -X982Y1744D01* -X2595Y1744D02* -X2602Y1744D01* -X1Y1743D02* -X8Y1743D01* -X275Y1743D02* -X281Y1743D01* -X975Y1743D02* -X981Y1743D01* -X2595Y1743D02* -X2602Y1743D01* -X1Y1742D02* -X8Y1742D01* -X274Y1742D02* -X280Y1742D01* -X974Y1742D02* -X980Y1742D01* -X2595Y1742D02* -X2602Y1742D01* -X1Y1741D02* -X8Y1741D01* -X273Y1741D02* -X279Y1741D01* -X973Y1741D02* -X979Y1741D01* -X2595Y1741D02* -X2602Y1741D01* -X1Y1740D02* -X8Y1740D01* -X272Y1740D02* -X278Y1740D01* -X972Y1740D02* -X978Y1740D01* -X2595Y1740D02* -X2602Y1740D01* -X1Y1739D02* -X8Y1739D01* -X271Y1739D02* -X277Y1739D01* -X971Y1739D02* -X977Y1739D01* -X2595Y1739D02* -X2602Y1739D01* -X1Y1738D02* -X8Y1738D01* -X270Y1738D02* -X276Y1738D01* -X970Y1738D02* -X976Y1738D01* -X2595Y1738D02* -X2602Y1738D01* -X1Y1737D02* -X8Y1737D01* -X269Y1737D02* -X275Y1737D01* -X969Y1737D02* -X975Y1737D01* -X2595Y1737D02* -X2602Y1737D01* -X1Y1736D02* -X8Y1736D01* -X268Y1736D02* -X274Y1736D01* -X968Y1736D02* -X974Y1736D01* -X2595Y1736D02* -X2602Y1736D01* -X1Y1735D02* -X8Y1735D01* -X267Y1735D02* -X273Y1735D01* -X967Y1735D02* -X973Y1735D01* -X2595Y1735D02* -X2602Y1735D01* -X1Y1734D02* -X8Y1734D01* -X266Y1734D02* -X272Y1734D01* -X966Y1734D02* -X972Y1734D01* -X2595Y1734D02* -X2602Y1734D01* -X1Y1733D02* -X8Y1733D01* -X265Y1733D02* -X271Y1733D01* -X965Y1733D02* -X971Y1733D01* -X2595Y1733D02* -X2602Y1733D01* -X1Y1732D02* -X8Y1732D01* -X264Y1732D02* -X270Y1732D01* -X964Y1732D02* -X969Y1732D01* -X2595Y1732D02* -X2602Y1732D01* -X1Y1731D02* -X8Y1731D01* -X263Y1731D02* -X268Y1731D01* -X963Y1731D02* -X968Y1731D01* -X2595Y1731D02* -X2602Y1731D01* -X1Y1730D02* -X8Y1730D01* -X262Y1730D02* -X268Y1730D01* -X962Y1730D02* -X967Y1730D01* -X2595Y1730D02* -X2602Y1730D01* -X1Y1729D02* -X8Y1729D01* -X261Y1729D02* -X267Y1729D01* -X961Y1729D02* -X967Y1729D01* -X2595Y1729D02* -X2602Y1729D01* -X1Y1728D02* -X8Y1728D01* -X260Y1728D02* -X266Y1728D01* -X960Y1728D02* -X966Y1728D01* -X2595Y1728D02* -X2602Y1728D01* -X1Y1727D02* -X8Y1727D01* -X259Y1727D02* -X265Y1727D01* -X959Y1727D02* -X965Y1727D01* -X2595Y1727D02* -X2602Y1727D01* -X1Y1726D02* -X8Y1726D01* -X258Y1726D02* -X264Y1726D01* -X958Y1726D02* -X964Y1726D01* -X2595Y1726D02* -X2602Y1726D01* -X1Y1725D02* -X8Y1725D01* -X257Y1725D02* -X263Y1725D01* -X957Y1725D02* -X963Y1725D01* -X2595Y1725D02* -X2602Y1725D01* -X1Y1724D02* -X8Y1724D01* -X256Y1724D02* -X262Y1724D01* -X956Y1724D02* -X962Y1724D01* -X2595Y1724D02* -X2602Y1724D01* -X1Y1723D02* -X8Y1723D01* -X255Y1723D02* -X261Y1723D01* -X955Y1723D02* -X961Y1723D01* -X2595Y1723D02* -X2602Y1723D01* -X1Y1722D02* -X8Y1722D01* -X254Y1722D02* -X260Y1722D01* -X954Y1722D02* -X960Y1722D01* -X2595Y1722D02* -X2602Y1722D01* -X1Y1721D02* -X8Y1721D01* -X253Y1721D02* -X259Y1721D01* -X953Y1721D02* -X959Y1721D01* -X2595Y1721D02* -X2602Y1721D01* -X1Y1720D02* -X8Y1720D01* -X252Y1720D02* -X258Y1720D01* -X952Y1720D02* -X958Y1720D01* -X2595Y1720D02* -X2602Y1720D01* -X1Y1719D02* -X8Y1719D01* -X251Y1719D02* -X257Y1719D01* -X951Y1719D02* -X957Y1719D01* -X2595Y1719D02* -X2602Y1719D01* -X1Y1718D02* -X8Y1718D01* -X250Y1718D02* -X256Y1718D01* -X950Y1718D02* -X956Y1718D01* -X2595Y1718D02* -X2602Y1718D01* -X1Y1717D02* -X8Y1717D01* -X249Y1717D02* -X255Y1717D01* -X949Y1717D02* -X955Y1717D01* -X2595Y1717D02* -X2602Y1717D01* -X1Y1716D02* -X8Y1716D01* -X249Y1716D02* -X254Y1716D01* -X949Y1716D02* -X954Y1716D01* -X2595Y1716D02* -X2602Y1716D01* -X1Y1715D02* -X8Y1715D01* -X250Y1715D02* -X253Y1715D01* -X950Y1715D02* -X953Y1715D01* -X2595Y1715D02* -X2602Y1715D01* -X1Y1714D02* -X8Y1714D01* -X251Y1714D02* -X252Y1714D01* -X951Y1714D02* -X952Y1714D01* -X2595Y1714D02* -X2602Y1714D01* -X1Y1713D02* -X8Y1713D01* -X2595Y1713D02* -X2602Y1713D01* -X1Y1712D02* -X8Y1712D01* -X2595Y1712D02* -X2602Y1712D01* -X1Y1711D02* -X8Y1711D01* -X2595Y1711D02* -X2602Y1711D01* -X1Y1710D02* -X8Y1710D01* -X2595Y1710D02* -X2602Y1710D01* -X1Y1709D02* -X8Y1709D01* -X2595Y1709D02* -X2602Y1709D01* -X1Y1708D02* -X8Y1708D01* -X2595Y1708D02* -X2602Y1708D01* -X1Y1707D02* -X8Y1707D01* -X2595Y1707D02* -X2602Y1707D01* -X1Y1706D02* -X8Y1706D01* -X2595Y1706D02* -X2602Y1706D01* -X1Y1705D02* -X8Y1705D01* -X2595Y1705D02* -X2602Y1705D01* -X1Y1704D02* -X8Y1704D01* -X2595Y1704D02* -X2602Y1704D01* -X1Y1703D02* -X8Y1703D01* -X2595Y1703D02* -X2602Y1703D01* -X1Y1702D02* -X8Y1702D01* -X2595Y1702D02* -X2602Y1702D01* -X1Y1701D02* -X8Y1701D01* -X2595Y1701D02* -X2602Y1701D01* -X1Y1700D02* -X8Y1700D01* -X2595Y1700D02* -X2602Y1700D01* -X1Y1699D02* -X8Y1699D01* -X2595Y1699D02* -X2602Y1699D01* -X1Y1698D02* -X8Y1698D01* -X2595Y1698D02* -X2602Y1698D01* -X1Y1697D02* -X8Y1697D01* -X2595Y1697D02* -X2602Y1697D01* -X1Y1696D02* -X8Y1696D01* -X2595Y1696D02* -X2602Y1696D01* -X1Y1695D02* -X8Y1695D01* -X2595Y1695D02* -X2602Y1695D01* -X1Y1694D02* -X8Y1694D01* -X2595Y1694D02* -X2602Y1694D01* -X1Y1693D02* -X8Y1693D01* -X2595Y1693D02* -X2602Y1693D01* -X1Y1692D02* -X8Y1692D01* -X2595Y1692D02* -X2602Y1692D01* -X1Y1691D02* -X8Y1691D01* -X2595Y1691D02* -X2602Y1691D01* -X1Y1690D02* -X8Y1690D01* -X2595Y1690D02* -X2602Y1690D01* -X1Y1689D02* -X8Y1689D01* -X2595Y1689D02* -X2602Y1689D01* -X1Y1688D02* -X8Y1688D01* -X2595Y1688D02* -X2602Y1688D01* -X1Y1687D02* -X8Y1687D01* -X2595Y1687D02* -X2602Y1687D01* -X1Y1686D02* -X8Y1686D01* -X2595Y1686D02* -X2602Y1686D01* -X1Y1685D02* -X8Y1685D01* -X1151Y1685D02* -X1152Y1685D01* -X2595Y1685D02* -X2602Y1685D01* -X1Y1684D02* -X8Y1684D01* -X1150Y1684D02* -X1153Y1684D01* -X2595Y1684D02* -X2602Y1684D01* -X1Y1683D02* -X8Y1683D01* -X1149Y1683D02* -X1154Y1683D01* -X2595Y1683D02* -X2602Y1683D01* -X1Y1682D02* -X8Y1682D01* -X1149Y1682D02* -X1155Y1682D01* -X2595Y1682D02* -X2602Y1682D01* -X1Y1681D02* -X8Y1681D01* -X1150Y1681D02* -X1156Y1681D01* -X2595Y1681D02* -X2602Y1681D01* -X1Y1680D02* -X8Y1680D01* -X1151Y1680D02* -X1157Y1680D01* -X2595Y1680D02* -X2602Y1680D01* -X1Y1679D02* -X8Y1679D01* -X1152Y1679D02* -X1158Y1679D01* -X2595Y1679D02* -X2602Y1679D01* -X1Y1678D02* -X8Y1678D01* -X1153Y1678D02* -X1159Y1678D01* -X2595Y1678D02* -X2602Y1678D01* -X1Y1677D02* -X8Y1677D01* -X1154Y1677D02* -X1160Y1677D01* -X2595Y1677D02* -X2602Y1677D01* -X1Y1676D02* -X8Y1676D01* -X1155Y1676D02* -X1161Y1676D01* -X2595Y1676D02* -X2602Y1676D01* -X1Y1675D02* -X8Y1675D01* -X1156Y1675D02* -X1162Y1675D01* -X2595Y1675D02* -X2602Y1675D01* -X1Y1674D02* -X8Y1674D01* -X1157Y1674D02* -X1163Y1674D01* -X2595Y1674D02* -X2602Y1674D01* -X1Y1673D02* -X8Y1673D01* -X1158Y1673D02* -X1164Y1673D01* -X2595Y1673D02* -X2602Y1673D01* -X1Y1672D02* -X8Y1672D01* -X1159Y1672D02* -X1165Y1672D01* -X2595Y1672D02* -X2602Y1672D01* -X1Y1671D02* -X8Y1671D01* -X1160Y1671D02* -X1166Y1671D01* -X2595Y1671D02* -X2602Y1671D01* -X1Y1670D02* -X8Y1670D01* -X1161Y1670D02* -X1167Y1670D01* -X2595Y1670D02* -X2602Y1670D01* -X1Y1669D02* -X8Y1669D01* -X1162Y1669D02* -X1167Y1669D01* -X2595Y1669D02* -X2602Y1669D01* -X1Y1668D02* -X8Y1668D01* -X1163Y1668D02* -X1168Y1668D01* -X2595Y1668D02* -X2602Y1668D01* -X1Y1667D02* -X8Y1667D01* -X1164Y1667D02* -X1170Y1667D01* -X2595Y1667D02* -X2602Y1667D01* -X1Y1666D02* -X8Y1666D01* -X1165Y1666D02* -X1171Y1666D01* -X2595Y1666D02* -X2602Y1666D01* -X1Y1665D02* -X8Y1665D01* -X1166Y1665D02* -X1172Y1665D01* -X2595Y1665D02* -X2602Y1665D01* -X1Y1664D02* -X8Y1664D01* -X1167Y1664D02* -X1173Y1664D01* -X2595Y1664D02* -X2602Y1664D01* -X1Y1663D02* -X8Y1663D01* -X1168Y1663D02* -X1174Y1663D01* -X2595Y1663D02* -X2602Y1663D01* -X1Y1662D02* -X8Y1662D01* -X1169Y1662D02* -X1175Y1662D01* -X2595Y1662D02* -X2602Y1662D01* -X1Y1661D02* -X8Y1661D01* -X1170Y1661D02* -X1176Y1661D01* -X2595Y1661D02* -X2602Y1661D01* -X1Y1660D02* -X8Y1660D01* -X1171Y1660D02* -X1177Y1660D01* -X2595Y1660D02* -X2602Y1660D01* -X1Y1659D02* -X8Y1659D01* -X1172Y1659D02* -X1178Y1659D01* -X2595Y1659D02* -X2602Y1659D01* -X1Y1658D02* -X8Y1658D01* -X1173Y1658D02* -X1179Y1658D01* -X2595Y1658D02* -X2602Y1658D01* -X1Y1657D02* -X8Y1657D01* -X1174Y1657D02* -X1180Y1657D01* -X2595Y1657D02* -X2602Y1657D01* -X1Y1656D02* -X8Y1656D01* -X1175Y1656D02* -X1181Y1656D01* -X2595Y1656D02* -X2602Y1656D01* -X1Y1655D02* -X8Y1655D01* -X1176Y1655D02* -X1182Y1655D01* -X2595Y1655D02* -X2602Y1655D01* -X1Y1654D02* -X8Y1654D01* -X1177Y1654D02* -X1183Y1654D01* -X2595Y1654D02* -X2602Y1654D01* -X1Y1653D02* -X8Y1653D01* -X1178Y1653D02* -X1184Y1653D01* -X2595Y1653D02* -X2602Y1653D01* -X1Y1652D02* -X8Y1652D01* -X1179Y1652D02* -X1185Y1652D01* -X2595Y1652D02* -X2602Y1652D01* -X1Y1651D02* -X8Y1651D01* -X1180Y1651D02* -X1185Y1651D01* -X2595Y1651D02* -X2602Y1651D01* -X1Y1650D02* -X8Y1650D01* -X1181Y1650D02* -X1185Y1650D01* -X2595Y1650D02* -X2602Y1650D01* -X1Y1649D02* -X8Y1649D01* -X1182Y1649D02* -X1184Y1649D01* -X2595Y1649D02* -X2602Y1649D01* -X1Y1648D02* -X8Y1648D01* -X2595Y1648D02* -X2602Y1648D01* -X1Y1647D02* -X8Y1647D01* -X2595Y1647D02* -X2602Y1647D01* -X1Y1646D02* -X8Y1646D01* -X2595Y1646D02* -X2602Y1646D01* -X1Y1645D02* -X8Y1645D01* -X2595Y1645D02* -X2602Y1645D01* -X1Y1644D02* -X8Y1644D01* -X2595Y1644D02* -X2602Y1644D01* -X1Y1643D02* -X8Y1643D01* -X2595Y1643D02* -X2602Y1643D01* -X1Y1642D02* -X8Y1642D01* -X2595Y1642D02* -X2602Y1642D01* -X1Y1641D02* -X8Y1641D01* -X2595Y1641D02* -X2602Y1641D01* -X1Y1640D02* -X8Y1640D01* -X2595Y1640D02* -X2602Y1640D01* -X1Y1639D02* -X8Y1639D01* -X2595Y1639D02* -X2602Y1639D01* -X1Y1638D02* -X8Y1638D01* -X2595Y1638D02* -X2602Y1638D01* -X1Y1637D02* -X8Y1637D01* -X2595Y1637D02* -X2602Y1637D01* -X1Y1636D02* -X8Y1636D01* -X2595Y1636D02* -X2602Y1636D01* -X1Y1635D02* -X8Y1635D01* -X2595Y1635D02* -X2602Y1635D01* -X1Y1634D02* -X8Y1634D01* -X2595Y1634D02* -X2602Y1634D01* -X1Y1633D02* -X8Y1633D01* -X2595Y1633D02* -X2602Y1633D01* -X1Y1632D02* -X8Y1632D01* -X2595Y1632D02* -X2602Y1632D01* -X1Y1631D02* -X8Y1631D01* -X2595Y1631D02* -X2602Y1631D01* -X1Y1630D02* -X8Y1630D01* -X2595Y1630D02* -X2602Y1630D01* -X1Y1629D02* -X8Y1629D01* -X2595Y1629D02* -X2602Y1629D01* -X1Y1628D02* -X8Y1628D01* -X2595Y1628D02* -X2602Y1628D01* -X1Y1627D02* -X8Y1627D01* -X2595Y1627D02* -X2602Y1627D01* -X1Y1626D02* -X8Y1626D01* -X2595Y1626D02* -X2602Y1626D01* -X1Y1625D02* -X8Y1625D01* -X2595Y1625D02* -X2602Y1625D01* -X1Y1624D02* -X8Y1624D01* -X2595Y1624D02* -X2602Y1624D01* -X1Y1623D02* -X8Y1623D01* -X2595Y1623D02* -X2602Y1623D01* -X1Y1622D02* -X8Y1622D01* -X2595Y1622D02* -X2602Y1622D01* -X1Y1621D02* -X8Y1621D01* -X2595Y1621D02* -X2602Y1621D01* -X1Y1620D02* -X8Y1620D01* -X2595Y1620D02* -X2602Y1620D01* -X1Y1619D02* -X8Y1619D01* -X2595Y1619D02* -X2602Y1619D01* -X1Y1618D02* -X8Y1618D01* -X2595Y1618D02* -X2602Y1618D01* -X1Y1617D02* -X8Y1617D01* -X2595Y1617D02* -X2602Y1617D01* -X1Y1616D02* -X8Y1616D01* -X2595Y1616D02* -X2602Y1616D01* -X1Y1615D02* -X8Y1615D01* -X2595Y1615D02* -X2602Y1615D01* -X1Y1614D02* -X8Y1614D01* -X2595Y1614D02* -X2602Y1614D01* -X1Y1613D02* -X8Y1613D01* -X2595Y1613D02* -X2602Y1613D01* -X1Y1612D02* -X8Y1612D01* -X2595Y1612D02* -X2602Y1612D01* -X1Y1611D02* -X8Y1611D01* -X2595Y1611D02* -X2602Y1611D01* -X1Y1610D02* -X8Y1610D01* -X2595Y1610D02* -X2602Y1610D01* -X1Y1609D02* -X8Y1609D01* -X2595Y1609D02* -X2602Y1609D01* -X1Y1608D02* -X8Y1608D01* -X2595Y1608D02* -X2602Y1608D01* -X1Y1607D02* -X8Y1607D01* -X2595Y1607D02* -X2602Y1607D01* -X1Y1606D02* -X8Y1606D01* -X2595Y1606D02* -X2602Y1606D01* -X1Y1605D02* -X8Y1605D01* -X2595Y1605D02* -X2602Y1605D01* -X1Y1604D02* -X8Y1604D01* -X2595Y1604D02* -X2602Y1604D01* -X1Y1603D02* -X8Y1603D01* -X2595Y1603D02* -X2602Y1603D01* -X1Y1602D02* -X8Y1602D01* -X2595Y1602D02* -X2602Y1602D01* -X1Y1601D02* -X8Y1601D01* -X2595Y1601D02* -X2602Y1601D01* -X1Y1600D02* -X8Y1600D01* -X2595Y1600D02* -X2602Y1600D01* -X1Y1599D02* -X8Y1599D01* -X2595Y1599D02* -X2602Y1599D01* -X1Y1598D02* -X8Y1598D01* -X2595Y1598D02* -X2602Y1598D01* -X1Y1597D02* -X8Y1597D01* -X2595Y1597D02* -X2602Y1597D01* -X1Y1596D02* -X8Y1596D01* -X2595Y1596D02* -X2602Y1596D01* -X1Y1595D02* -X8Y1595D01* -X2595Y1595D02* -X2602Y1595D01* -X1Y1594D02* -X8Y1594D01* -X2595Y1594D02* -X2602Y1594D01* -X1Y1593D02* -X8Y1593D01* -X2595Y1593D02* -X2602Y1593D01* -X1Y1592D02* -X8Y1592D01* -X2595Y1592D02* -X2602Y1592D01* -X1Y1591D02* -X8Y1591D01* -X2595Y1591D02* -X2602Y1591D01* -X1Y1590D02* -X8Y1590D01* -X2595Y1590D02* -X2602Y1590D01* -X1Y1589D02* -X8Y1589D01* -X2595Y1589D02* -X2602Y1589D01* -X1Y1588D02* -X8Y1588D01* -X2595Y1588D02* -X2602Y1588D01* -X1Y1587D02* -X8Y1587D01* -X2595Y1587D02* -X2602Y1587D01* -X1Y1586D02* -X8Y1586D01* -X2595Y1586D02* -X2602Y1586D01* -X1Y1585D02* -X8Y1585D01* -X2595Y1585D02* -X2602Y1585D01* -X1Y1584D02* -X8Y1584D01* -X2595Y1584D02* -X2602Y1584D01* -X1Y1583D02* -X8Y1583D01* -X2595Y1583D02* -X2602Y1583D01* -X1Y1582D02* -X8Y1582D01* -X2595Y1582D02* -X2602Y1582D01* -X1Y1581D02* -X8Y1581D01* -X2595Y1581D02* -X2602Y1581D01* -X1Y1580D02* -X8Y1580D01* -X2595Y1580D02* -X2602Y1580D01* -X1Y1579D02* -X8Y1579D01* -X2595Y1579D02* -X2602Y1579D01* -X1Y1578D02* -X8Y1578D01* -X2595Y1578D02* -X2602Y1578D01* -X1Y1577D02* -X8Y1577D01* -X2595Y1577D02* -X2602Y1577D01* -X1Y1576D02* -X8Y1576D01* -X2595Y1576D02* -X2602Y1576D01* -X1Y1575D02* -X8Y1575D01* -X2595Y1575D02* -X2602Y1575D01* -X1Y1574D02* -X8Y1574D01* -X2595Y1574D02* -X2602Y1574D01* -X1Y1573D02* -X8Y1573D01* -X2595Y1573D02* -X2602Y1573D01* -X1Y1572D02* -X8Y1572D01* -X2595Y1572D02* -X2602Y1572D01* -X1Y1571D02* -X8Y1571D01* -X2595Y1571D02* -X2602Y1571D01* -X1Y1570D02* -X8Y1570D01* -X2595Y1570D02* -X2602Y1570D01* -X1Y1569D02* -X8Y1569D01* -X2595Y1569D02* -X2602Y1569D01* -X1Y1568D02* -X8Y1568D01* -X2595Y1568D02* -X2602Y1568D01* -X1Y1567D02* -X8Y1567D01* -X2595Y1567D02* -X2602Y1567D01* -X1Y1566D02* -X8Y1566D01* -X2595Y1566D02* -X2602Y1566D01* -X1Y1565D02* -X8Y1565D01* -X2595Y1565D02* -X2602Y1565D01* -X1Y1564D02* -X8Y1564D01* -X2595Y1564D02* -X2602Y1564D01* -X1Y1563D02* -X8Y1563D01* -X2595Y1563D02* -X2602Y1563D01* -X1Y1562D02* -X8Y1562D01* -X2595Y1562D02* -X2602Y1562D01* -X1Y1561D02* -X8Y1561D01* -X2595Y1561D02* -X2602Y1561D01* -X1Y1560D02* -X8Y1560D01* -X2595Y1560D02* -X2602Y1560D01* -X1Y1559D02* -X8Y1559D01* -X2595Y1559D02* -X2602Y1559D01* -X1Y1558D02* -X8Y1558D01* -X2595Y1558D02* -X2602Y1558D01* -X1Y1557D02* -X8Y1557D01* -X2595Y1557D02* -X2602Y1557D01* -X1Y1556D02* -X8Y1556D01* -X2595Y1556D02* -X2602Y1556D01* -X1Y1555D02* -X8Y1555D01* -X2595Y1555D02* -X2602Y1555D01* -X1Y1554D02* -X8Y1554D01* -X2595Y1554D02* -X2602Y1554D01* -X1Y1553D02* -X8Y1553D01* -X2595Y1553D02* -X2602Y1553D01* -X1Y1552D02* -X8Y1552D01* -X2595Y1552D02* -X2602Y1552D01* -X1Y1551D02* -X8Y1551D01* -X2595Y1551D02* -X2602Y1551D01* -X1Y1550D02* -X8Y1550D01* -X2595Y1550D02* -X2602Y1550D01* -X1Y1549D02* -X8Y1549D01* -X2595Y1549D02* -X2602Y1549D01* -X1Y1548D02* -X8Y1548D01* -X2595Y1548D02* -X2602Y1548D01* -X1Y1547D02* -X8Y1547D01* -X2595Y1547D02* -X2602Y1547D01* -X1Y1546D02* -X8Y1546D01* -X2595Y1546D02* -X2602Y1546D01* -X1Y1545D02* -X8Y1545D01* -X2595Y1545D02* -X2602Y1545D01* -X1Y1544D02* -X8Y1544D01* -X2595Y1544D02* -X2602Y1544D01* -X1Y1543D02* -X8Y1543D01* -X2595Y1543D02* -X2602Y1543D01* -X1Y1542D02* -X8Y1542D01* -X2595Y1542D02* -X2602Y1542D01* -X1Y1541D02* -X8Y1541D01* -X2595Y1541D02* -X2602Y1541D01* -X1Y1540D02* -X8Y1540D01* -X2595Y1540D02* -X2602Y1540D01* -X1Y1539D02* -X8Y1539D01* -X2595Y1539D02* -X2602Y1539D01* -X1Y1538D02* -X8Y1538D01* -X2595Y1538D02* -X2602Y1538D01* -X1Y1537D02* -X8Y1537D01* -X2595Y1537D02* -X2602Y1537D01* -X1Y1536D02* -X8Y1536D01* -X2595Y1536D02* -X2602Y1536D01* -X1Y1535D02* -X8Y1535D01* -X2595Y1535D02* -X2602Y1535D01* -X1Y1534D02* -X8Y1534D01* -X2595Y1534D02* -X2602Y1534D01* -X1Y1533D02* -X8Y1533D01* -X2595Y1533D02* -X2602Y1533D01* -X1Y1532D02* -X8Y1532D01* -X2595Y1532D02* -X2602Y1532D01* -X1Y1531D02* -X8Y1531D01* -X2595Y1531D02* -X2602Y1531D01* -X1Y1530D02* -X8Y1530D01* -X2595Y1530D02* -X2602Y1530D01* -X1Y1529D02* -X8Y1529D01* -X2595Y1529D02* -X2602Y1529D01* -X1Y1528D02* -X8Y1528D01* -X2595Y1528D02* -X2602Y1528D01* -X1Y1527D02* -X8Y1527D01* -X2595Y1527D02* -X2602Y1527D01* -X1Y1526D02* -X8Y1526D01* -X2595Y1526D02* -X2602Y1526D01* -X1Y1525D02* -X8Y1525D01* -X2595Y1525D02* -X2602Y1525D01* -X1Y1524D02* -X8Y1524D01* -X2595Y1524D02* -X2602Y1524D01* -X1Y1523D02* -X8Y1523D01* -X2595Y1523D02* -X2602Y1523D01* -X1Y1522D02* -X8Y1522D01* -X2595Y1522D02* -X2602Y1522D01* -X1Y1521D02* -X8Y1521D01* -X2595Y1521D02* -X2602Y1521D01* -X1Y1520D02* -X8Y1520D01* -X2595Y1520D02* -X2602Y1520D01* -X1Y1519D02* -X8Y1519D01* -X2595Y1519D02* -X2602Y1519D01* -X1Y1518D02* -X8Y1518D01* -X2595Y1518D02* -X2602Y1518D01* -X1Y1517D02* -X8Y1517D01* -X2595Y1517D02* -X2602Y1517D01* -X1Y1516D02* -X8Y1516D01* -X2595Y1516D02* -X2602Y1516D01* -X1Y1515D02* -X8Y1515D01* -X2595Y1515D02* -X2602Y1515D01* -X1Y1514D02* -X8Y1514D01* -X2595Y1514D02* -X2602Y1514D01* -X1Y1513D02* -X8Y1513D01* -X2595Y1513D02* -X2602Y1513D01* -X1Y1512D02* -X8Y1512D01* -X2595Y1512D02* -X2602Y1512D01* -X1Y1511D02* -X8Y1511D01* -X2595Y1511D02* -X2602Y1511D01* -X1Y1510D02* -X8Y1510D01* -X2595Y1510D02* -X2602Y1510D01* -X1Y1509D02* -X8Y1509D01* -X2595Y1509D02* -X2602Y1509D01* -X1Y1508D02* -X8Y1508D01* -X2595Y1508D02* -X2602Y1508D01* -X1Y1507D02* -X8Y1507D01* -X2595Y1507D02* -X2602Y1507D01* -X1Y1506D02* -X8Y1506D01* -X2595Y1506D02* -X2602Y1506D01* -X1Y1505D02* -X8Y1505D01* -X2595Y1505D02* -X2602Y1505D01* -X1Y1504D02* -X8Y1504D01* -X2595Y1504D02* -X2602Y1504D01* -X1Y1503D02* -X8Y1503D01* -X2595Y1503D02* -X2602Y1503D01* -X1Y1502D02* -X8Y1502D01* -X2595Y1502D02* -X2602Y1502D01* -X1Y1501D02* -X8Y1501D01* -X2595Y1501D02* -X2602Y1501D01* -X1Y1500D02* -X8Y1500D01* -X2595Y1500D02* -X2602Y1500D01* -X1Y1499D02* -X8Y1499D01* -X2595Y1499D02* -X2602Y1499D01* -X1Y1498D02* -X8Y1498D01* -X2595Y1498D02* -X2602Y1498D01* -X1Y1497D02* -X8Y1497D01* -X2595Y1497D02* -X2602Y1497D01* -X1Y1496D02* -X8Y1496D01* -X2595Y1496D02* -X2602Y1496D01* -X1Y1495D02* -X8Y1495D01* -X2595Y1495D02* -X2602Y1495D01* -X1Y1494D02* -X8Y1494D01* -X2595Y1494D02* -X2602Y1494D01* -X1Y1493D02* -X8Y1493D01* -X2595Y1493D02* -X2602Y1493D01* -X1Y1492D02* -X8Y1492D01* -X2595Y1492D02* -X2602Y1492D01* -X1Y1491D02* -X8Y1491D01* -X2595Y1491D02* -X2602Y1491D01* -X1Y1490D02* -X8Y1490D01* -X2595Y1490D02* -X2602Y1490D01* -X1Y1489D02* -X8Y1489D01* -X2595Y1489D02* -X2602Y1489D01* -X1Y1488D02* -X8Y1488D01* -X2595Y1488D02* -X2602Y1488D01* -X1Y1487D02* -X8Y1487D01* -X2595Y1487D02* -X2602Y1487D01* -X1Y1486D02* -X8Y1486D01* -X2595Y1486D02* -X2602Y1486D01* -X1Y1485D02* -X8Y1485D01* -X2595Y1485D02* -X2602Y1485D01* -X1Y1484D02* -X8Y1484D01* -X2595Y1484D02* -X2602Y1484D01* -X1Y1483D02* -X8Y1483D01* -X2595Y1483D02* -X2602Y1483D01* -X1Y1482D02* -X8Y1482D01* -X2595Y1482D02* -X2602Y1482D01* -X1Y1481D02* -X8Y1481D01* -X2595Y1481D02* -X2602Y1481D01* -X1Y1480D02* -X8Y1480D01* -X2595Y1480D02* -X2602Y1480D01* -X1Y1479D02* -X8Y1479D01* -X2595Y1479D02* -X2602Y1479D01* -X1Y1478D02* -X8Y1478D01* -X2595Y1478D02* -X2602Y1478D01* -X1Y1477D02* -X8Y1477D01* -X2595Y1477D02* -X2602Y1477D01* -X1Y1476D02* -X8Y1476D01* -X2595Y1476D02* -X2602Y1476D01* -X1Y1475D02* -X8Y1475D01* -X2595Y1475D02* -X2602Y1475D01* -X1Y1474D02* -X8Y1474D01* -X2595Y1474D02* -X2602Y1474D01* -X1Y1473D02* -X8Y1473D01* -X2595Y1473D02* -X2602Y1473D01* -X1Y1472D02* -X8Y1472D01* -X2595Y1472D02* -X2602Y1472D01* -X1Y1471D02* -X8Y1471D01* -X2595Y1471D02* -X2602Y1471D01* -X1Y1470D02* -X8Y1470D01* -X2595Y1470D02* -X2602Y1470D01* -X1Y1469D02* -X8Y1469D01* -X2595Y1469D02* -X2602Y1469D01* -X1Y1468D02* -X8Y1468D01* -X2595Y1468D02* -X2602Y1468D01* -X1Y1467D02* -X8Y1467D01* -X2595Y1467D02* -X2602Y1467D01* -X1Y1466D02* -X8Y1466D01* -X2595Y1466D02* -X2602Y1466D01* -X1Y1465D02* -X8Y1465D01* -X2595Y1465D02* -X2602Y1465D01* -X1Y1464D02* -X8Y1464D01* -X2595Y1464D02* -X2602Y1464D01* -X1Y1463D02* -X8Y1463D01* -X2595Y1463D02* -X2602Y1463D01* -X1Y1462D02* -X8Y1462D01* -X2595Y1462D02* -X2602Y1462D01* -X1Y1461D02* -X8Y1461D01* -X2595Y1461D02* -X2602Y1461D01* -X1Y1460D02* -X8Y1460D01* -X2595Y1460D02* -X2602Y1460D01* -X1Y1459D02* -X8Y1459D01* -X2595Y1459D02* -X2602Y1459D01* -X1Y1458D02* -X8Y1458D01* -X2595Y1458D02* -X2602Y1458D01* -X1Y1457D02* -X8Y1457D01* -X2595Y1457D02* -X2602Y1457D01* -X1Y1456D02* -X8Y1456D01* -X2595Y1456D02* -X2602Y1456D01* -X1Y1455D02* -X8Y1455D01* -X2595Y1455D02* -X2602Y1455D01* -X1Y1454D02* -X8Y1454D01* -X2595Y1454D02* -X2602Y1454D01* -X1Y1453D02* -X8Y1453D01* -X2595Y1453D02* -X2602Y1453D01* -X1Y1452D02* -X8Y1452D01* -X2595Y1452D02* -X2602Y1452D01* -X1Y1451D02* -X8Y1451D01* -X2595Y1451D02* -X2602Y1451D01* -X1Y1450D02* -X8Y1450D01* -X2595Y1450D02* -X2602Y1450D01* -X1Y1449D02* -X8Y1449D01* -X2595Y1449D02* -X2602Y1449D01* -X1Y1448D02* -X8Y1448D01* -X2595Y1448D02* -X2602Y1448D01* -X1Y1447D02* -X8Y1447D01* -X2595Y1447D02* -X2602Y1447D01* -X1Y1446D02* -X8Y1446D01* -X2595Y1446D02* -X2602Y1446D01* -X1Y1445D02* -X8Y1445D01* -X2595Y1445D02* -X2602Y1445D01* -X1Y1444D02* -X8Y1444D01* -X2595Y1444D02* -X2602Y1444D01* -X1Y1443D02* -X8Y1443D01* -X2595Y1443D02* -X2602Y1443D01* -X1Y1442D02* -X8Y1442D01* -X2595Y1442D02* -X2602Y1442D01* -X1Y1441D02* -X8Y1441D01* -X2595Y1441D02* -X2602Y1441D01* -X1Y1440D02* -X8Y1440D01* -X2595Y1440D02* -X2602Y1440D01* -X1Y1439D02* -X8Y1439D01* -X2595Y1439D02* -X2602Y1439D01* -X1Y1438D02* -X8Y1438D01* -X2595Y1438D02* -X2602Y1438D01* -X1Y1437D02* -X8Y1437D01* -X2595Y1437D02* -X2602Y1437D01* -X1Y1436D02* -X8Y1436D01* -X2595Y1436D02* -X2602Y1436D01* -X1Y1435D02* -X8Y1435D01* -X2595Y1435D02* -X2602Y1435D01* -X1Y1434D02* -X8Y1434D01* -X2595Y1434D02* -X2602Y1434D01* -X1Y1433D02* -X8Y1433D01* -X2595Y1433D02* -X2602Y1433D01* -X1Y1432D02* -X8Y1432D01* -X2595Y1432D02* -X2602Y1432D01* -X1Y1431D02* -X8Y1431D01* -X2595Y1431D02* -X2602Y1431D01* -X1Y1430D02* -X8Y1430D01* -X2595Y1430D02* -X2602Y1430D01* -X1Y1429D02* -X8Y1429D01* -X2595Y1429D02* -X2602Y1429D01* -X1Y1428D02* -X8Y1428D01* -X2595Y1428D02* -X2602Y1428D01* -X1Y1427D02* -X8Y1427D01* -X2595Y1427D02* -X2602Y1427D01* -X1Y1426D02* -X8Y1426D01* -X2595Y1426D02* -X2602Y1426D01* -X1Y1425D02* -X8Y1425D01* -X2595Y1425D02* -X2602Y1425D01* -X1Y1424D02* -X8Y1424D01* -X2595Y1424D02* -X2602Y1424D01* -X1Y1423D02* -X8Y1423D01* -X2595Y1423D02* -X2602Y1423D01* -X1Y1422D02* -X8Y1422D01* -X2595Y1422D02* -X2602Y1422D01* -X1Y1421D02* -X8Y1421D01* -X2595Y1421D02* -X2602Y1421D01* -X1Y1420D02* -X8Y1420D01* -X2595Y1420D02* -X2602Y1420D01* -X1Y1419D02* -X8Y1419D01* -X2595Y1419D02* -X2602Y1419D01* -X1Y1418D02* -X8Y1418D01* -X2595Y1418D02* -X2602Y1418D01* -X1Y1417D02* -X8Y1417D01* -X2595Y1417D02* -X2602Y1417D01* -X1Y1416D02* -X8Y1416D01* -X2595Y1416D02* -X2602Y1416D01* -X1Y1415D02* -X8Y1415D01* -X2595Y1415D02* -X2602Y1415D01* -X1Y1414D02* -X8Y1414D01* -X2595Y1414D02* -X2602Y1414D01* -X1Y1413D02* -X8Y1413D01* -X2595Y1413D02* -X2602Y1413D01* -X1Y1412D02* -X8Y1412D01* -X2595Y1412D02* -X2602Y1412D01* -X1Y1411D02* -X8Y1411D01* -X2595Y1411D02* -X2602Y1411D01* -X1Y1410D02* -X8Y1410D01* -X2595Y1410D02* -X2602Y1410D01* -X1Y1409D02* -X8Y1409D01* -X2595Y1409D02* -X2602Y1409D01* -X1Y1408D02* -X8Y1408D01* -X2595Y1408D02* -X2602Y1408D01* -X1Y1407D02* -X8Y1407D01* -X2595Y1407D02* -X2602Y1407D01* -X1Y1406D02* -X8Y1406D01* -X2595Y1406D02* -X2602Y1406D01* -X1Y1405D02* -X8Y1405D01* -X2595Y1405D02* -X2602Y1405D01* -X1Y1404D02* -X8Y1404D01* -X2595Y1404D02* -X2602Y1404D01* -X1Y1403D02* -X8Y1403D01* -X2595Y1403D02* -X2602Y1403D01* -X1Y1402D02* -X8Y1402D01* -X2595Y1402D02* -X2602Y1402D01* -X1Y1401D02* -X8Y1401D01* -X2595Y1401D02* -X2602Y1401D01* -X1Y1400D02* -X8Y1400D01* -X2595Y1400D02* -X2602Y1400D01* -X1Y1399D02* -X8Y1399D01* -X2595Y1399D02* -X2602Y1399D01* -X1Y1398D02* -X8Y1398D01* -X2595Y1398D02* -X2602Y1398D01* -X1Y1397D02* -X8Y1397D01* -X2595Y1397D02* -X2602Y1397D01* -X1Y1396D02* -X8Y1396D01* -X2595Y1396D02* -X2602Y1396D01* -X1Y1395D02* -X8Y1395D01* -X2595Y1395D02* -X2602Y1395D01* -X1Y1394D02* -X8Y1394D01* -X2595Y1394D02* -X2602Y1394D01* -X1Y1393D02* -X8Y1393D01* -X2595Y1393D02* -X2602Y1393D01* -X1Y1392D02* -X8Y1392D01* -X2595Y1392D02* -X2602Y1392D01* -X1Y1391D02* -X8Y1391D01* -X2595Y1391D02* -X2602Y1391D01* -X1Y1390D02* -X8Y1390D01* -X2595Y1390D02* -X2602Y1390D01* -X1Y1389D02* -X8Y1389D01* -X2595Y1389D02* -X2602Y1389D01* -X1Y1388D02* -X8Y1388D01* -X2595Y1388D02* -X2602Y1388D01* -X1Y1387D02* -X8Y1387D01* -X2595Y1387D02* -X2602Y1387D01* -X1Y1386D02* -X8Y1386D01* -X2595Y1386D02* -X2602Y1386D01* -X1Y1385D02* -X8Y1385D01* -X2595Y1385D02* -X2602Y1385D01* -X1Y1384D02* -X8Y1384D01* -X2595Y1384D02* -X2602Y1384D01* -X1Y1383D02* -X8Y1383D01* -X2595Y1383D02* -X2602Y1383D01* -X1Y1382D02* -X8Y1382D01* -X2595Y1382D02* -X2602Y1382D01* -X1Y1381D02* -X8Y1381D01* -X2595Y1381D02* -X2602Y1381D01* -X1Y1380D02* -X8Y1380D01* -X2595Y1380D02* -X2602Y1380D01* -X1Y1379D02* -X8Y1379D01* -X2595Y1379D02* -X2602Y1379D01* -X1Y1378D02* -X8Y1378D01* -X2595Y1378D02* -X2602Y1378D01* -X1Y1377D02* -X8Y1377D01* -X2595Y1377D02* -X2602Y1377D01* -X1Y1376D02* -X8Y1376D01* -X2595Y1376D02* -X2602Y1376D01* -X1Y1375D02* -X8Y1375D01* -X2595Y1375D02* -X2602Y1375D01* -X1Y1374D02* -X8Y1374D01* -X2595Y1374D02* -X2602Y1374D01* -X1Y1373D02* -X8Y1373D01* -X2595Y1373D02* -X2602Y1373D01* -X1Y1372D02* -X8Y1372D01* -X2595Y1372D02* -X2602Y1372D01* -X1Y1371D02* -X8Y1371D01* -X2595Y1371D02* -X2602Y1371D01* -X1Y1370D02* -X8Y1370D01* -X2595Y1370D02* -X2602Y1370D01* -X1Y1369D02* -X8Y1369D01* -X2595Y1369D02* -X2602Y1369D01* -X1Y1368D02* -X8Y1368D01* -X2595Y1368D02* -X2602Y1368D01* -X1Y1367D02* -X8Y1367D01* -X2595Y1367D02* -X2602Y1367D01* -X1Y1366D02* -X8Y1366D01* -X2595Y1366D02* -X2602Y1366D01* -X1Y1365D02* -X8Y1365D01* -X2595Y1365D02* -X2602Y1365D01* -X1Y1364D02* -X8Y1364D01* -X2595Y1364D02* -X2602Y1364D01* -X1Y1363D02* -X8Y1363D01* -X2595Y1363D02* -X2602Y1363D01* -X1Y1362D02* -X8Y1362D01* -X2595Y1362D02* -X2602Y1362D01* -X1Y1361D02* -X8Y1361D01* -X2595Y1361D02* -X2602Y1361D01* -X1Y1360D02* -X8Y1360D01* -X2595Y1360D02* -X2602Y1360D01* -X1Y1359D02* -X8Y1359D01* -X2595Y1359D02* -X2602Y1359D01* -X1Y1358D02* -X8Y1358D01* -X2595Y1358D02* -X2602Y1358D01* -X1Y1357D02* -X8Y1357D01* -X2595Y1357D02* -X2602Y1357D01* -X1Y1356D02* -X8Y1356D01* -X2595Y1356D02* -X2602Y1356D01* -X1Y1355D02* -X8Y1355D01* -X2595Y1355D02* -X2602Y1355D01* -X1Y1354D02* -X8Y1354D01* -X2595Y1354D02* -X2602Y1354D01* -X1Y1353D02* -X8Y1353D01* -X2595Y1353D02* -X2602Y1353D01* -X1Y1352D02* -X8Y1352D01* -X2595Y1352D02* -X2602Y1352D01* -X1Y1351D02* -X8Y1351D01* -X2595Y1351D02* -X2602Y1351D01* -X1Y1350D02* -X8Y1350D01* -X2595Y1350D02* -X2602Y1350D01* -X1Y1349D02* -X8Y1349D01* -X2595Y1349D02* -X2602Y1349D01* -X1Y1348D02* -X8Y1348D01* -X2595Y1348D02* -X2602Y1348D01* -X1Y1347D02* -X8Y1347D01* -X2595Y1347D02* -X2602Y1347D01* -X1Y1346D02* -X8Y1346D01* -X2595Y1346D02* -X2602Y1346D01* -X1Y1345D02* -X8Y1345D01* -X2595Y1345D02* -X2602Y1345D01* -X1Y1344D02* -X8Y1344D01* -X2595Y1344D02* -X2602Y1344D01* -X1Y1343D02* -X8Y1343D01* -X2595Y1343D02* -X2602Y1343D01* -X1Y1342D02* -X8Y1342D01* -X2595Y1342D02* -X2602Y1342D01* -X1Y1341D02* -X8Y1341D01* -X2595Y1341D02* -X2602Y1341D01* -X1Y1340D02* -X8Y1340D01* -X2595Y1340D02* -X2602Y1340D01* -X1Y1339D02* -X8Y1339D01* -X2595Y1339D02* -X2602Y1339D01* -X1Y1338D02* -X8Y1338D01* -X2595Y1338D02* -X2602Y1338D01* -X1Y1337D02* -X8Y1337D01* -X2595Y1337D02* -X2602Y1337D01* -X1Y1336D02* -X8Y1336D01* -X2595Y1336D02* -X2602Y1336D01* -X1Y1335D02* -X8Y1335D01* -X2595Y1335D02* -X2602Y1335D01* -X1Y1334D02* -X8Y1334D01* -X2595Y1334D02* -X2602Y1334D01* -X1Y1333D02* -X8Y1333D01* -X2595Y1333D02* -X2602Y1333D01* -X1Y1332D02* -X8Y1332D01* -X2595Y1332D02* -X2602Y1332D01* -X1Y1331D02* -X8Y1331D01* -X2595Y1331D02* -X2602Y1331D01* -X1Y1330D02* -X8Y1330D01* -X2595Y1330D02* -X2602Y1330D01* -X1Y1329D02* -X8Y1329D01* -X2595Y1329D02* -X2602Y1329D01* -X1Y1328D02* -X8Y1328D01* -X2595Y1328D02* -X2602Y1328D01* -X1Y1327D02* -X8Y1327D01* -X2595Y1327D02* -X2602Y1327D01* -X1Y1326D02* -X8Y1326D01* -X2595Y1326D02* -X2602Y1326D01* -X1Y1325D02* -X8Y1325D01* -X2595Y1325D02* -X2602Y1325D01* -X1Y1324D02* -X8Y1324D01* -X2595Y1324D02* -X2602Y1324D01* -X1Y1323D02* -X8Y1323D01* -X2595Y1323D02* -X2602Y1323D01* -X1Y1322D02* -X8Y1322D01* -X2595Y1322D02* -X2602Y1322D01* -X1Y1321D02* -X8Y1321D01* -X2595Y1321D02* -X2602Y1321D01* -X1Y1320D02* -X8Y1320D01* -X2595Y1320D02* -X2602Y1320D01* -X1Y1319D02* -X8Y1319D01* -X2595Y1319D02* -X2602Y1319D01* -X1Y1318D02* -X8Y1318D01* -X2595Y1318D02* -X2602Y1318D01* -X1Y1317D02* -X8Y1317D01* -X2595Y1317D02* -X2602Y1317D01* -X1Y1316D02* -X8Y1316D01* -X2595Y1316D02* -X2602Y1316D01* -X1Y1315D02* -X8Y1315D01* -X2595Y1315D02* -X2602Y1315D01* -X1Y1314D02* -X8Y1314D01* -X2595Y1314D02* -X2602Y1314D01* -X1Y1313D02* -X8Y1313D01* -X2595Y1313D02* -X2602Y1313D01* -X1Y1312D02* -X8Y1312D01* -X2595Y1312D02* -X2602Y1312D01* -X1Y1311D02* -X8Y1311D01* -X2595Y1311D02* -X2602Y1311D01* -X1Y1310D02* -X8Y1310D01* -X2595Y1310D02* -X2602Y1310D01* -X1Y1309D02* -X8Y1309D01* -X2595Y1309D02* -X2602Y1309D01* -X1Y1308D02* -X8Y1308D01* -X2595Y1308D02* -X2602Y1308D01* -X1Y1307D02* -X8Y1307D01* -X2595Y1307D02* -X2602Y1307D01* -X1Y1306D02* -X8Y1306D01* -X2595Y1306D02* -X2602Y1306D01* -X1Y1305D02* -X8Y1305D01* -X2595Y1305D02* -X2602Y1305D01* -X1Y1304D02* -X8Y1304D01* -X2595Y1304D02* -X2602Y1304D01* -X1Y1303D02* -X8Y1303D01* -X2595Y1303D02* -X2602Y1303D01* -X1Y1302D02* -X8Y1302D01* -X2595Y1302D02* -X2602Y1302D01* -X1Y1301D02* -X8Y1301D01* -X2595Y1301D02* -X2602Y1301D01* -X1Y1300D02* -X8Y1300D01* -X2595Y1300D02* -X2602Y1300D01* -X1Y1299D02* -X8Y1299D01* -X2595Y1299D02* -X2602Y1299D01* -X1Y1298D02* -X8Y1298D01* -X2595Y1298D02* -X2602Y1298D01* -X1Y1297D02* -X8Y1297D01* -X2595Y1297D02* -X2602Y1297D01* -X1Y1296D02* -X8Y1296D01* -X2595Y1296D02* -X2602Y1296D01* -X1Y1295D02* -X8Y1295D01* -X2595Y1295D02* -X2602Y1295D01* -X1Y1294D02* -X8Y1294D01* -X2595Y1294D02* -X2602Y1294D01* -X1Y1293D02* -X8Y1293D01* -X2595Y1293D02* -X2602Y1293D01* -X1Y1292D02* -X8Y1292D01* -X2595Y1292D02* -X2602Y1292D01* -X1Y1291D02* -X8Y1291D01* -X2595Y1291D02* -X2602Y1291D01* -X1Y1290D02* -X8Y1290D01* -X2595Y1290D02* -X2602Y1290D01* -X1Y1289D02* -X8Y1289D01* -X2595Y1289D02* -X2602Y1289D01* -X1Y1288D02* -X8Y1288D01* -X2595Y1288D02* -X2602Y1288D01* -X1Y1287D02* -X8Y1287D01* -X2595Y1287D02* -X2602Y1287D01* -X1Y1286D02* -X8Y1286D01* -X2595Y1286D02* -X2602Y1286D01* -X1Y1285D02* -X8Y1285D01* -X2595Y1285D02* -X2602Y1285D01* -X1Y1284D02* -X8Y1284D01* -X2595Y1284D02* -X2602Y1284D01* -X1Y1283D02* -X8Y1283D01* -X2595Y1283D02* -X2602Y1283D01* -X1Y1282D02* -X8Y1282D01* -X2595Y1282D02* -X2602Y1282D01* -X1Y1281D02* -X8Y1281D01* -X2595Y1281D02* -X2602Y1281D01* -X1Y1280D02* -X8Y1280D01* -X2595Y1280D02* -X2602Y1280D01* -X1Y1279D02* -X8Y1279D01* -X2595Y1279D02* -X2602Y1279D01* -X1Y1278D02* -X8Y1278D01* -X2595Y1278D02* -X2602Y1278D01* -X1Y1277D02* -X8Y1277D01* -X2595Y1277D02* -X2602Y1277D01* -X1Y1276D02* -X8Y1276D01* -X2595Y1276D02* -X2602Y1276D01* -X1Y1275D02* -X8Y1275D01* -X2595Y1275D02* -X2602Y1275D01* -X1Y1274D02* -X8Y1274D01* -X2595Y1274D02* -X2602Y1274D01* -X1Y1273D02* -X8Y1273D01* -X2595Y1273D02* -X2602Y1273D01* -X1Y1272D02* -X8Y1272D01* -X2595Y1272D02* -X2602Y1272D01* -X1Y1271D02* -X8Y1271D01* -X2595Y1271D02* -X2602Y1271D01* -X1Y1270D02* -X8Y1270D01* -X2595Y1270D02* -X2602Y1270D01* -X1Y1269D02* -X8Y1269D01* -X2595Y1269D02* -X2602Y1269D01* -X1Y1268D02* -X8Y1268D01* -X2595Y1268D02* -X2602Y1268D01* -X1Y1267D02* -X8Y1267D01* -X2595Y1267D02* -X2602Y1267D01* -X1Y1266D02* -X8Y1266D01* -X2595Y1266D02* -X2602Y1266D01* -X1Y1265D02* -X8Y1265D01* -X2595Y1265D02* -X2602Y1265D01* -X1Y1264D02* -X8Y1264D01* -X2595Y1264D02* -X2602Y1264D01* -X1Y1263D02* -X8Y1263D01* -X2595Y1263D02* -X2602Y1263D01* -X1Y1262D02* -X8Y1262D01* -X2595Y1262D02* -X2602Y1262D01* -X1Y1261D02* -X8Y1261D01* -X2595Y1261D02* -X2602Y1261D01* -X1Y1260D02* -X8Y1260D01* -X2595Y1260D02* -X2602Y1260D01* -X1Y1259D02* -X8Y1259D01* -X2595Y1259D02* -X2602Y1259D01* -X1Y1258D02* -X8Y1258D01* -X2595Y1258D02* -X2602Y1258D01* -X1Y1257D02* -X8Y1257D01* -X2595Y1257D02* -X2602Y1257D01* -X1Y1256D02* -X8Y1256D01* -X2595Y1256D02* -X2602Y1256D01* -X1Y1255D02* -X8Y1255D01* -X2595Y1255D02* -X2602Y1255D01* -X1Y1254D02* -X8Y1254D01* -X2595Y1254D02* -X2602Y1254D01* -X1Y1253D02* -X8Y1253D01* -X2595Y1253D02* -X2602Y1253D01* -X1Y1252D02* -X8Y1252D01* -X2595Y1252D02* -X2602Y1252D01* -X1Y1251D02* -X8Y1251D01* -X2595Y1251D02* -X2602Y1251D01* -X1Y1250D02* -X8Y1250D01* -X2595Y1250D02* -X2602Y1250D01* -X1Y1249D02* -X8Y1249D01* -X2595Y1249D02* -X2602Y1249D01* -X1Y1248D02* -X8Y1248D01* -X2595Y1248D02* -X2602Y1248D01* -X1Y1247D02* -X8Y1247D01* -X2595Y1247D02* -X2602Y1247D01* -X1Y1246D02* -X8Y1246D01* -X2595Y1246D02* -X2602Y1246D01* -X1Y1245D02* -X8Y1245D01* -X2595Y1245D02* -X2602Y1245D01* -X1Y1244D02* -X8Y1244D01* -X2595Y1244D02* -X2602Y1244D01* -X1Y1243D02* -X8Y1243D01* -X2595Y1243D02* -X2602Y1243D01* -X1Y1242D02* -X8Y1242D01* -X2595Y1242D02* -X2602Y1242D01* -X1Y1241D02* -X8Y1241D01* -X2595Y1241D02* -X2602Y1241D01* -X1Y1240D02* -X8Y1240D01* -X2595Y1240D02* -X2602Y1240D01* -X1Y1239D02* -X8Y1239D01* -X2595Y1239D02* -X2602Y1239D01* -X1Y1238D02* -X8Y1238D01* -X2595Y1238D02* -X2602Y1238D01* -X1Y1237D02* -X8Y1237D01* -X2595Y1237D02* -X2602Y1237D01* -X1Y1236D02* -X8Y1236D01* -X2595Y1236D02* -X2602Y1236D01* -X1Y1235D02* -X8Y1235D01* -X2595Y1235D02* -X2602Y1235D01* -X1Y1234D02* -X8Y1234D01* -X2595Y1234D02* -X2602Y1234D01* -X1Y1233D02* -X8Y1233D01* -X2595Y1233D02* -X2602Y1233D01* -X1Y1232D02* -X8Y1232D01* -X2595Y1232D02* -X2602Y1232D01* -X1Y1231D02* -X8Y1231D01* -X2595Y1231D02* -X2602Y1231D01* -X1Y1230D02* -X8Y1230D01* -X2595Y1230D02* -X2602Y1230D01* -X1Y1229D02* -X8Y1229D01* -X2595Y1229D02* -X2602Y1229D01* -X1Y1228D02* -X8Y1228D01* -X2595Y1228D02* -X2602Y1228D01* -X1Y1227D02* -X8Y1227D01* -X2595Y1227D02* -X2602Y1227D01* -X1Y1226D02* -X8Y1226D01* -X2595Y1226D02* -X2602Y1226D01* -X1Y1225D02* -X8Y1225D01* -X2595Y1225D02* -X2602Y1225D01* -X1Y1224D02* -X8Y1224D01* -X2595Y1224D02* -X2602Y1224D01* -X1Y1223D02* -X8Y1223D01* -X2595Y1223D02* -X2602Y1223D01* -X1Y1222D02* -X8Y1222D01* -X2595Y1222D02* -X2602Y1222D01* -X1Y1221D02* -X8Y1221D01* -X2595Y1221D02* -X2602Y1221D01* -X1Y1220D02* -X8Y1220D01* -X2595Y1220D02* -X2602Y1220D01* -X1Y1219D02* -X8Y1219D01* -X2595Y1219D02* -X2602Y1219D01* -X1Y1218D02* -X8Y1218D01* -X2595Y1218D02* -X2602Y1218D01* -X1Y1217D02* -X8Y1217D01* -X2595Y1217D02* -X2602Y1217D01* -X1Y1216D02* -X8Y1216D01* -X2595Y1216D02* -X2602Y1216D01* -X1Y1215D02* -X8Y1215D01* -X2595Y1215D02* -X2602Y1215D01* -X1Y1214D02* -X8Y1214D01* -X2595Y1214D02* -X2602Y1214D01* -X1Y1213D02* -X8Y1213D01* -X2595Y1213D02* -X2602Y1213D01* -X1Y1212D02* -X8Y1212D01* -X2595Y1212D02* -X2602Y1212D01* -X1Y1211D02* -X8Y1211D01* -X2595Y1211D02* -X2602Y1211D01* -X1Y1210D02* -X8Y1210D01* -X2595Y1210D02* -X2602Y1210D01* -X1Y1209D02* -X8Y1209D01* -X2595Y1209D02* -X2602Y1209D01* -X1Y1208D02* -X8Y1208D01* -X2595Y1208D02* -X2602Y1208D01* -X1Y1207D02* -X8Y1207D01* -X2595Y1207D02* -X2602Y1207D01* -X1Y1206D02* -X8Y1206D01* -X2595Y1206D02* -X2602Y1206D01* -X1Y1205D02* -X8Y1205D01* -X2595Y1205D02* -X2602Y1205D01* -X1Y1204D02* -X8Y1204D01* -X2595Y1204D02* -X2602Y1204D01* -X1Y1203D02* -X8Y1203D01* -X2595Y1203D02* -X2602Y1203D01* -X1Y1202D02* -X8Y1202D01* -X2595Y1202D02* -X2602Y1202D01* -X1Y1201D02* -X8Y1201D01* -X2595Y1201D02* -X2602Y1201D01* -X1Y1200D02* -X8Y1200D01* -X2595Y1200D02* -X2602Y1200D01* -X1Y1199D02* -X8Y1199D01* -X2595Y1199D02* -X2602Y1199D01* -X1Y1198D02* -X8Y1198D01* -X2595Y1198D02* -X2602Y1198D01* -X1Y1197D02* -X8Y1197D01* -X2595Y1197D02* -X2602Y1197D01* -X1Y1196D02* -X8Y1196D01* -X2595Y1196D02* -X2602Y1196D01* -X1Y1195D02* -X8Y1195D01* -X2595Y1195D02* -X2602Y1195D01* -X1Y1194D02* -X8Y1194D01* -X2595Y1194D02* -X2602Y1194D01* -X1Y1193D02* -X8Y1193D01* -X2595Y1193D02* -X2602Y1193D01* -X1Y1192D02* -X8Y1192D01* -X2595Y1192D02* -X2602Y1192D01* -X1Y1191D02* -X8Y1191D01* -X2595Y1191D02* -X2602Y1191D01* -X1Y1190D02* -X8Y1190D01* -X2595Y1190D02* -X2602Y1190D01* -X1Y1189D02* -X8Y1189D01* -X2595Y1189D02* -X2602Y1189D01* -X1Y1188D02* -X8Y1188D01* -X2595Y1188D02* -X2602Y1188D01* -X1Y1187D02* -X8Y1187D01* -X2595Y1187D02* -X2602Y1187D01* -X1Y1186D02* -X8Y1186D01* -X2595Y1186D02* -X2602Y1186D01* -X1Y1185D02* -X8Y1185D01* -X2595Y1185D02* -X2602Y1185D01* -X1Y1184D02* -X8Y1184D01* -X2595Y1184D02* -X2602Y1184D01* -X1Y1183D02* -X8Y1183D01* -X2595Y1183D02* -X2602Y1183D01* -X1Y1182D02* -X8Y1182D01* -X2595Y1182D02* -X2602Y1182D01* -X1Y1181D02* -X8Y1181D01* -X2595Y1181D02* -X2602Y1181D01* -X1Y1180D02* -X8Y1180D01* -X2595Y1180D02* -X2602Y1180D01* -X1Y1179D02* -X8Y1179D01* -X2595Y1179D02* -X2602Y1179D01* -X1Y1178D02* -X8Y1178D01* -X2595Y1178D02* -X2602Y1178D01* -X1Y1177D02* -X8Y1177D01* -X2595Y1177D02* -X2602Y1177D01* -X1Y1176D02* -X8Y1176D01* -X2595Y1176D02* -X2602Y1176D01* -X1Y1175D02* -X8Y1175D01* -X2595Y1175D02* -X2602Y1175D01* -X1Y1174D02* -X8Y1174D01* -X2595Y1174D02* -X2602Y1174D01* -X1Y1173D02* -X8Y1173D01* -X2595Y1173D02* -X2602Y1173D01* -X1Y1172D02* -X8Y1172D01* -X2595Y1172D02* -X2602Y1172D01* -X1Y1171D02* -X8Y1171D01* -X2595Y1171D02* -X2602Y1171D01* -X1Y1170D02* -X8Y1170D01* -X2595Y1170D02* -X2602Y1170D01* -X1Y1169D02* -X8Y1169D01* -X2595Y1169D02* -X2602Y1169D01* -X1Y1168D02* -X8Y1168D01* -X2595Y1168D02* -X2602Y1168D01* -X1Y1167D02* -X8Y1167D01* -X2595Y1167D02* -X2602Y1167D01* -X1Y1166D02* -X8Y1166D01* -X2595Y1166D02* -X2602Y1166D01* -X1Y1165D02* -X8Y1165D01* -X2595Y1165D02* -X2602Y1165D01* -X1Y1164D02* -X8Y1164D01* -X2595Y1164D02* -X2602Y1164D01* -X1Y1163D02* -X8Y1163D01* -X2595Y1163D02* -X2602Y1163D01* -X1Y1162D02* -X8Y1162D01* -X2595Y1162D02* -X2602Y1162D01* -X1Y1161D02* -X8Y1161D01* -X2595Y1161D02* -X2602Y1161D01* -X1Y1160D02* -X8Y1160D01* -X2595Y1160D02* -X2602Y1160D01* -X1Y1159D02* -X8Y1159D01* -X2595Y1159D02* -X2602Y1159D01* -X1Y1158D02* -X8Y1158D01* -X2595Y1158D02* -X2602Y1158D01* -X1Y1157D02* -X8Y1157D01* -X2595Y1157D02* -X2602Y1157D01* -X1Y1156D02* -X8Y1156D01* -X2595Y1156D02* -X2602Y1156D01* -X1Y1155D02* -X8Y1155D01* -X2595Y1155D02* -X2602Y1155D01* -X1Y1154D02* -X8Y1154D01* -X2595Y1154D02* -X2602Y1154D01* -X1Y1153D02* -X8Y1153D01* -X2595Y1153D02* -X2602Y1153D01* -X1Y1152D02* -X8Y1152D01* -X2595Y1152D02* -X2602Y1152D01* -X1Y1151D02* -X8Y1151D01* -X2595Y1151D02* -X2602Y1151D01* -X1Y1150D02* -X8Y1150D01* -X2595Y1150D02* -X2602Y1150D01* -X1Y1149D02* -X8Y1149D01* -X2595Y1149D02* -X2602Y1149D01* -X1Y1148D02* -X8Y1148D01* -X2595Y1148D02* -X2602Y1148D01* -X1Y1147D02* -X8Y1147D01* -X2595Y1147D02* -X2602Y1147D01* -X1Y1146D02* -X8Y1146D01* -X2595Y1146D02* -X2602Y1146D01* -X1Y1145D02* -X8Y1145D01* -X2595Y1145D02* -X2602Y1145D01* -X1Y1144D02* -X8Y1144D01* -X2595Y1144D02* -X2602Y1144D01* -X1Y1143D02* -X8Y1143D01* -X2595Y1143D02* -X2602Y1143D01* -X1Y1142D02* -X8Y1142D01* -X2595Y1142D02* -X2602Y1142D01* -X1Y1141D02* -X8Y1141D01* -X2595Y1141D02* -X2602Y1141D01* -X1Y1140D02* -X8Y1140D01* -X2595Y1140D02* -X2602Y1140D01* -X1Y1139D02* -X8Y1139D01* -X2595Y1139D02* -X2602Y1139D01* -X1Y1138D02* -X8Y1138D01* -X2595Y1138D02* -X2602Y1138D01* -X1Y1137D02* -X8Y1137D01* -X2595Y1137D02* -X2602Y1137D01* -X1Y1136D02* -X8Y1136D01* -X2595Y1136D02* -X2602Y1136D01* -X1Y1135D02* -X8Y1135D01* -X2595Y1135D02* -X2602Y1135D01* -X1Y1134D02* -X8Y1134D01* -X2595Y1134D02* -X2602Y1134D01* -X1Y1133D02* -X8Y1133D01* -X2595Y1133D02* -X2602Y1133D01* -X1Y1132D02* -X8Y1132D01* -X2595Y1132D02* -X2602Y1132D01* -X1Y1131D02* -X8Y1131D01* -X2595Y1131D02* -X2602Y1131D01* -X1Y1130D02* -X8Y1130D01* -X2595Y1130D02* -X2602Y1130D01* -X1Y1129D02* -X8Y1129D01* -X2595Y1129D02* -X2602Y1129D01* -X1Y1128D02* -X8Y1128D01* -X2595Y1128D02* -X2602Y1128D01* -X1Y1127D02* -X8Y1127D01* -X2595Y1127D02* -X2602Y1127D01* -X1Y1126D02* -X8Y1126D01* -X2595Y1126D02* -X2602Y1126D01* -X1Y1125D02* -X8Y1125D01* -X2595Y1125D02* -X2602Y1125D01* -X1Y1124D02* -X8Y1124D01* -X2595Y1124D02* -X2602Y1124D01* -X1Y1123D02* -X8Y1123D01* -X2595Y1123D02* -X2602Y1123D01* -X1Y1122D02* -X8Y1122D01* -X2595Y1122D02* -X2602Y1122D01* -X1Y1121D02* -X8Y1121D01* -X2595Y1121D02* -X2602Y1121D01* -X1Y1120D02* -X8Y1120D01* -X2595Y1120D02* -X2602Y1120D01* -X1Y1119D02* -X8Y1119D01* -X2595Y1119D02* -X2602Y1119D01* -X1Y1118D02* -X8Y1118D01* -X2595Y1118D02* -X2602Y1118D01* -X1Y1117D02* -X8Y1117D01* -X2595Y1117D02* -X2602Y1117D01* -X1Y1116D02* -X8Y1116D01* -X2595Y1116D02* -X2602Y1116D01* -X1Y1115D02* -X8Y1115D01* -X2595Y1115D02* -X2602Y1115D01* -X1Y1114D02* -X8Y1114D01* -X2595Y1114D02* -X2602Y1114D01* -X1Y1113D02* -X8Y1113D01* -X2595Y1113D02* -X2602Y1113D01* -X1Y1112D02* -X8Y1112D01* -X2595Y1112D02* -X2602Y1112D01* -X1Y1111D02* -X8Y1111D01* -X2595Y1111D02* -X2602Y1111D01* -X1Y1110D02* -X8Y1110D01* -X2595Y1110D02* -X2602Y1110D01* -X1Y1109D02* -X8Y1109D01* -X2595Y1109D02* -X2602Y1109D01* -X1Y1108D02* -X8Y1108D01* -X2595Y1108D02* -X2602Y1108D01* -X1Y1107D02* -X8Y1107D01* -X2595Y1107D02* -X2602Y1107D01* -X1Y1106D02* -X8Y1106D01* -X2595Y1106D02* -X2602Y1106D01* -X1Y1105D02* -X8Y1105D01* -X2595Y1105D02* -X2602Y1105D01* -X1Y1104D02* -X8Y1104D01* -X2595Y1104D02* -X2602Y1104D01* -X1Y1103D02* -X8Y1103D01* -X2595Y1103D02* -X2602Y1103D01* -X1Y1102D02* -X8Y1102D01* -X2595Y1102D02* -X2602Y1102D01* -X1Y1101D02* -X8Y1101D01* -X2595Y1101D02* -X2602Y1101D01* -X1Y1100D02* -X8Y1100D01* -X2595Y1100D02* -X2602Y1100D01* -X1Y1099D02* -X8Y1099D01* -X2595Y1099D02* -X2602Y1099D01* -X1Y1098D02* -X8Y1098D01* -X2595Y1098D02* -X2602Y1098D01* -X1Y1097D02* -X8Y1097D01* -X2595Y1097D02* -X2602Y1097D01* -X1Y1096D02* -X8Y1096D01* -X2595Y1096D02* -X2602Y1096D01* -X1Y1095D02* -X8Y1095D01* -X2595Y1095D02* -X2602Y1095D01* -X1Y1094D02* -X8Y1094D01* -X2595Y1094D02* -X2602Y1094D01* -X1Y1093D02* -X8Y1093D01* -X2595Y1093D02* -X2602Y1093D01* -X1Y1092D02* -X8Y1092D01* -X2595Y1092D02* -X2602Y1092D01* -X1Y1091D02* -X8Y1091D01* -X2595Y1091D02* -X2602Y1091D01* -X1Y1090D02* -X8Y1090D01* -X2595Y1090D02* -X2602Y1090D01* -X1Y1089D02* -X8Y1089D01* -X2595Y1089D02* -X2602Y1089D01* -X1Y1088D02* -X8Y1088D01* -X2595Y1088D02* -X2602Y1088D01* -X1Y1087D02* -X8Y1087D01* -X2595Y1087D02* -X2602Y1087D01* -X1Y1086D02* -X8Y1086D01* -X2595Y1086D02* -X2602Y1086D01* -X1Y1085D02* -X8Y1085D01* -X2595Y1085D02* -X2602Y1085D01* -X1Y1084D02* -X8Y1084D01* -X2595Y1084D02* -X2602Y1084D01* -X1Y1083D02* -X8Y1083D01* -X2595Y1083D02* -X2602Y1083D01* -X1Y1082D02* -X8Y1082D01* -X2595Y1082D02* -X2602Y1082D01* -X1Y1081D02* -X8Y1081D01* -X2595Y1081D02* -X2602Y1081D01* -X1Y1080D02* -X8Y1080D01* -X2595Y1080D02* -X2602Y1080D01* -X1Y1079D02* -X8Y1079D01* -X2595Y1079D02* -X2602Y1079D01* -X1Y1078D02* -X8Y1078D01* -X2595Y1078D02* -X2602Y1078D01* -X1Y1077D02* -X8Y1077D01* -X2595Y1077D02* -X2602Y1077D01* -X1Y1076D02* -X8Y1076D01* -X2595Y1076D02* -X2602Y1076D01* -X1Y1075D02* -X8Y1075D01* -X2595Y1075D02* -X2602Y1075D01* -X1Y1074D02* -X8Y1074D01* -X2595Y1074D02* -X2602Y1074D01* -X1Y1073D02* -X8Y1073D01* -X2595Y1073D02* -X2602Y1073D01* -X1Y1072D02* -X8Y1072D01* -X2595Y1072D02* -X2602Y1072D01* -X1Y1071D02* -X8Y1071D01* -X2595Y1071D02* -X2602Y1071D01* -X1Y1070D02* -X8Y1070D01* -X2595Y1070D02* -X2602Y1070D01* -X1Y1069D02* -X8Y1069D01* -X2595Y1069D02* -X2602Y1069D01* -X1Y1068D02* -X8Y1068D01* -X2595Y1068D02* -X2602Y1068D01* -X1Y1067D02* -X8Y1067D01* -X2595Y1067D02* -X2602Y1067D01* -X1Y1066D02* -X8Y1066D01* -X2595Y1066D02* -X2602Y1066D01* -X1Y1065D02* -X8Y1065D01* -X2595Y1065D02* -X2602Y1065D01* -X1Y1064D02* -X8Y1064D01* -X2595Y1064D02* -X2602Y1064D01* -X1Y1063D02* -X8Y1063D01* -X2595Y1063D02* -X2602Y1063D01* -X1Y1062D02* -X8Y1062D01* -X2595Y1062D02* -X2602Y1062D01* -X1Y1061D02* -X8Y1061D01* -X2595Y1061D02* -X2602Y1061D01* -X1Y1060D02* -X8Y1060D01* -X2595Y1060D02* -X2602Y1060D01* -X1Y1059D02* -X8Y1059D01* -X2595Y1059D02* -X2602Y1059D01* -X1Y1058D02* -X8Y1058D01* -X2595Y1058D02* -X2602Y1058D01* -X1Y1057D02* -X8Y1057D01* -X2595Y1057D02* -X2602Y1057D01* -X1Y1056D02* -X8Y1056D01* -X2595Y1056D02* -X2602Y1056D01* -X1Y1055D02* -X8Y1055D01* -X2595Y1055D02* -X2602Y1055D01* -X1Y1054D02* -X8Y1054D01* -X2595Y1054D02* -X2602Y1054D01* -X1Y1053D02* -X8Y1053D01* -X2595Y1053D02* -X2602Y1053D01* -X1Y1052D02* -X8Y1052D01* -X2595Y1052D02* -X2602Y1052D01* -X1Y1051D02* -X8Y1051D01* -X2595Y1051D02* -X2602Y1051D01* -X1Y1050D02* -X8Y1050D01* -X2595Y1050D02* -X2602Y1050D01* -X1Y1049D02* -X8Y1049D01* -X2595Y1049D02* -X2602Y1049D01* -X1Y1048D02* -X8Y1048D01* -X2595Y1048D02* -X2602Y1048D01* -X1Y1047D02* -X8Y1047D01* -X2595Y1047D02* -X2602Y1047D01* -X1Y1046D02* -X8Y1046D01* -X2595Y1046D02* -X2602Y1046D01* -X1Y1045D02* -X8Y1045D01* -X2595Y1045D02* -X2602Y1045D01* -X1Y1044D02* -X8Y1044D01* -X2595Y1044D02* -X2602Y1044D01* -X1Y1043D02* -X8Y1043D01* -X2595Y1043D02* -X2602Y1043D01* -X1Y1042D02* -X8Y1042D01* -X2595Y1042D02* -X2602Y1042D01* -X1Y1041D02* -X8Y1041D01* -X2595Y1041D02* -X2602Y1041D01* -X1Y1040D02* -X8Y1040D01* -X2595Y1040D02* -X2602Y1040D01* -X1Y1039D02* -X8Y1039D01* -X2595Y1039D02* -X2602Y1039D01* -X1Y1038D02* -X8Y1038D01* -X2595Y1038D02* -X2602Y1038D01* -X1Y1037D02* -X8Y1037D01* -X2595Y1037D02* -X2602Y1037D01* -X1Y1036D02* -X8Y1036D01* -X2595Y1036D02* -X2602Y1036D01* -X1Y1035D02* -X8Y1035D01* -X2595Y1035D02* -X2602Y1035D01* -X1Y1034D02* -X8Y1034D01* -X2595Y1034D02* -X2602Y1034D01* -X1Y1033D02* -X8Y1033D01* -X2595Y1033D02* -X2602Y1033D01* -X1Y1032D02* -X8Y1032D01* -X2595Y1032D02* -X2602Y1032D01* -X1Y1031D02* -X8Y1031D01* -X2595Y1031D02* -X2602Y1031D01* -X1Y1030D02* -X8Y1030D01* -X2595Y1030D02* -X2602Y1030D01* -X1Y1029D02* -X8Y1029D01* -X2595Y1029D02* -X2602Y1029D01* -X1Y1028D02* -X8Y1028D01* -X2595Y1028D02* -X2602Y1028D01* -X1Y1027D02* -X8Y1027D01* -X2595Y1027D02* -X2602Y1027D01* -X1Y1026D02* -X8Y1026D01* -X2595Y1026D02* -X2602Y1026D01* -X1Y1025D02* -X8Y1025D01* -X2595Y1025D02* -X2602Y1025D01* -X1Y1024D02* -X8Y1024D01* -X2595Y1024D02* -X2602Y1024D01* -X1Y1023D02* -X8Y1023D01* -X2595Y1023D02* -X2602Y1023D01* -X1Y1022D02* -X8Y1022D01* -X2595Y1022D02* -X2602Y1022D01* -X1Y1021D02* -X8Y1021D01* -X2595Y1021D02* -X2602Y1021D01* -X1Y1020D02* -X8Y1020D01* -X2595Y1020D02* -X2602Y1020D01* -X1Y1019D02* -X8Y1019D01* -X2595Y1019D02* -X2602Y1019D01* -X1Y1018D02* -X8Y1018D01* -X2595Y1018D02* -X2602Y1018D01* -X1Y1017D02* -X8Y1017D01* -X2595Y1017D02* -X2602Y1017D01* -X1Y1016D02* -X8Y1016D01* -X2595Y1016D02* -X2602Y1016D01* -X1Y1015D02* -X8Y1015D01* -X2595Y1015D02* -X2602Y1015D01* -X1Y1014D02* -X8Y1014D01* -X2595Y1014D02* -X2602Y1014D01* -X1Y1013D02* -X8Y1013D01* -X2595Y1013D02* -X2602Y1013D01* -X1Y1012D02* -X8Y1012D01* -X2595Y1012D02* -X2602Y1012D01* -X1Y1011D02* -X8Y1011D01* -X2595Y1011D02* -X2602Y1011D01* -X1Y1010D02* -X8Y1010D01* -X2595Y1010D02* -X2602Y1010D01* -X1Y1009D02* -X8Y1009D01* -X2595Y1009D02* -X2602Y1009D01* -X1Y1008D02* -X8Y1008D01* -X2595Y1008D02* -X2602Y1008D01* -X1Y1007D02* -X8Y1007D01* -X2595Y1007D02* -X2602Y1007D01* -X1Y1006D02* -X8Y1006D01* -X2595Y1006D02* -X2602Y1006D01* -X1Y1005D02* -X8Y1005D01* -X2595Y1005D02* -X2602Y1005D01* -X1Y1004D02* -X8Y1004D01* -X2595Y1004D02* -X2602Y1004D01* -X1Y1003D02* -X8Y1003D01* -X2595Y1003D02* -X2602Y1003D01* -X1Y1002D02* -X8Y1002D01* -X2595Y1002D02* -X2602Y1002D01* -X1Y1001D02* -X8Y1001D01* -X2595Y1001D02* -X2602Y1001D01* -X1Y1000D02* -X8Y1000D01* -X2595Y1000D02* -X2602Y1000D01* -X1Y999D02* -X8Y999D01* -X2595Y999D02* -X2602Y999D01* -X1Y998D02* -X8Y998D01* -X2595Y998D02* -X2602Y998D01* -X1Y997D02* -X8Y997D01* -X2595Y997D02* -X2602Y997D01* -X1Y996D02* -X8Y996D01* -X2595Y996D02* -X2602Y996D01* -X1Y995D02* -X8Y995D01* -X2595Y995D02* -X2602Y995D01* -X1Y994D02* -X8Y994D01* -X2595Y994D02* -X2602Y994D01* -X1Y993D02* -X8Y993D01* -X2595Y993D02* -X2602Y993D01* -X1Y992D02* -X8Y992D01* -X2595Y992D02* -X2602Y992D01* -X1Y991D02* -X8Y991D01* -X2595Y991D02* -X2602Y991D01* -X1Y990D02* -X8Y990D01* -X2595Y990D02* -X2602Y990D01* -X1Y989D02* -X8Y989D01* -X2595Y989D02* -X2602Y989D01* -X1Y988D02* -X8Y988D01* -X2595Y988D02* -X2602Y988D01* -X1Y987D02* -X8Y987D01* -X2595Y987D02* -X2602Y987D01* -X1Y986D02* -X8Y986D01* -X2595Y986D02* -X2602Y986D01* -X1Y985D02* -X8Y985D01* -X2595Y985D02* -X2602Y985D01* -X1Y984D02* -X8Y984D01* -X2595Y984D02* -X2602Y984D01* -X1Y983D02* -X8Y983D01* -X2595Y983D02* -X2602Y983D01* -X1Y982D02* -X8Y982D01* -X2595Y982D02* -X2602Y982D01* -X1Y981D02* -X8Y981D01* -X2595Y981D02* -X2602Y981D01* -X1Y980D02* -X8Y980D01* -X2595Y980D02* -X2602Y980D01* -X1Y979D02* -X8Y979D01* -X2595Y979D02* -X2602Y979D01* -X1Y978D02* -X8Y978D01* -X2595Y978D02* -X2602Y978D01* -X1Y977D02* -X8Y977D01* -X2595Y977D02* -X2602Y977D01* -X1Y976D02* -X8Y976D01* -X2595Y976D02* -X2602Y976D01* -X1Y975D02* -X8Y975D01* -X2595Y975D02* -X2602Y975D01* -X1Y974D02* -X8Y974D01* -X2595Y974D02* -X2602Y974D01* -X1Y973D02* -X8Y973D01* -X2595Y973D02* -X2602Y973D01* -X1Y972D02* -X8Y972D01* -X2595Y972D02* -X2602Y972D01* -X1Y971D02* -X8Y971D01* -X2595Y971D02* -X2602Y971D01* -X1Y970D02* -X8Y970D01* -X2595Y970D02* -X2602Y970D01* -X1Y969D02* -X8Y969D01* -X2595Y969D02* -X2602Y969D01* -X1Y968D02* -X8Y968D01* -X2595Y968D02* -X2602Y968D01* -X1Y967D02* -X8Y967D01* -X2595Y967D02* -X2602Y967D01* -X1Y966D02* -X8Y966D01* -X2595Y966D02* -X2602Y966D01* -X1Y965D02* -X8Y965D01* -X2595Y965D02* -X2602Y965D01* -X1Y964D02* -X8Y964D01* -X2595Y964D02* -X2602Y964D01* -X1Y963D02* -X8Y963D01* -X2595Y963D02* -X2602Y963D01* -X1Y962D02* -X8Y962D01* -X2595Y962D02* -X2602Y962D01* -X1Y961D02* -X8Y961D01* -X2595Y961D02* -X2602Y961D01* -X1Y960D02* -X8Y960D01* -X2595Y960D02* -X2602Y960D01* -X1Y959D02* -X8Y959D01* -X2595Y959D02* -X2602Y959D01* -X1Y958D02* -X8Y958D01* -X2595Y958D02* -X2602Y958D01* -X1Y957D02* -X8Y957D01* -X2595Y957D02* -X2602Y957D01* -X1Y956D02* -X8Y956D01* -X2595Y956D02* -X2602Y956D01* -X1Y955D02* -X8Y955D01* -X2595Y955D02* -X2602Y955D01* -X1Y954D02* -X8Y954D01* -X2595Y954D02* -X2602Y954D01* -X1Y953D02* -X8Y953D01* -X2595Y953D02* -X2602Y953D01* -X1Y952D02* -X8Y952D01* -X2595Y952D02* -X2602Y952D01* -X1Y951D02* -X8Y951D01* -X2595Y951D02* -X2602Y951D01* -X1Y950D02* -X8Y950D01* -X2595Y950D02* -X2602Y950D01* -X1Y949D02* -X8Y949D01* -X2595Y949D02* -X2602Y949D01* -X1Y948D02* -X8Y948D01* -X2595Y948D02* -X2602Y948D01* -X1Y947D02* -X8Y947D01* -X2595Y947D02* -X2602Y947D01* -X1Y946D02* -X8Y946D01* -X2595Y946D02* -X2602Y946D01* -X1Y945D02* -X8Y945D01* -X2595Y945D02* -X2602Y945D01* -X1Y944D02* -X8Y944D01* -X2595Y944D02* -X2602Y944D01* -X1Y943D02* -X8Y943D01* -X2595Y943D02* -X2602Y943D01* -X1Y942D02* -X8Y942D01* -X2595Y942D02* -X2602Y942D01* -X1Y941D02* -X8Y941D01* -X2595Y941D02* -X2602Y941D01* -X1Y940D02* -X8Y940D01* -X2595Y940D02* -X2602Y940D01* -X1Y939D02* -X8Y939D01* -X2595Y939D02* -X2602Y939D01* -X1Y938D02* -X8Y938D01* -X2595Y938D02* -X2602Y938D01* -X1Y937D02* -X8Y937D01* -X2595Y937D02* -X2602Y937D01* -X1Y936D02* -X8Y936D01* -X2595Y936D02* -X2602Y936D01* -X1Y935D02* -X8Y935D01* -X2595Y935D02* -X2602Y935D01* -X1Y934D02* -X8Y934D01* -X2595Y934D02* -X2602Y934D01* -X1Y933D02* -X8Y933D01* -X2595Y933D02* -X2602Y933D01* -X1Y932D02* -X8Y932D01* -X2595Y932D02* -X2602Y932D01* -X1Y931D02* -X8Y931D01* -X2595Y931D02* -X2602Y931D01* -X1Y930D02* -X8Y930D01* -X2595Y930D02* -X2602Y930D01* -X1Y929D02* -X8Y929D01* -X2595Y929D02* -X2602Y929D01* -X1Y928D02* -X8Y928D01* -X2595Y928D02* -X2602Y928D01* -X1Y927D02* -X8Y927D01* -X2595Y927D02* -X2602Y927D01* -X1Y926D02* -X8Y926D01* -X2595Y926D02* -X2602Y926D01* -X1Y925D02* -X8Y925D01* -X2595Y925D02* -X2602Y925D01* -X1Y924D02* -X8Y924D01* -X2595Y924D02* -X2602Y924D01* -X1Y923D02* -X8Y923D01* -X2595Y923D02* -X2602Y923D01* -X1Y922D02* -X8Y922D01* -X2595Y922D02* -X2602Y922D01* -X1Y921D02* -X8Y921D01* -X2595Y921D02* -X2602Y921D01* -X1Y920D02* -X8Y920D01* -X2595Y920D02* -X2602Y920D01* -X1Y919D02* -X8Y919D01* -X2595Y919D02* -X2602Y919D01* -X1Y918D02* -X8Y918D01* -X2595Y918D02* -X2602Y918D01* -X1Y917D02* -X8Y917D01* -X2595Y917D02* -X2602Y917D01* -X1Y916D02* -X8Y916D01* -X2595Y916D02* -X2602Y916D01* -X1Y915D02* -X8Y915D01* -X2595Y915D02* -X2602Y915D01* -X1Y914D02* -X8Y914D01* -X2595Y914D02* -X2602Y914D01* -X1Y913D02* -X8Y913D01* -X2595Y913D02* -X2602Y913D01* -X1Y912D02* -X8Y912D01* -X2595Y912D02* -X2602Y912D01* -X1Y911D02* -X8Y911D01* -X2595Y911D02* -X2602Y911D01* -X1Y910D02* -X8Y910D01* -X2595Y910D02* -X2602Y910D01* -X1Y909D02* -X8Y909D01* -X2595Y909D02* -X2602Y909D01* -X1Y908D02* -X8Y908D01* -X2595Y908D02* -X2602Y908D01* -X1Y907D02* -X8Y907D01* -X2595Y907D02* -X2602Y907D01* -X1Y906D02* -X8Y906D01* -X2595Y906D02* -X2602Y906D01* -X1Y905D02* -X8Y905D01* -X2595Y905D02* -X2602Y905D01* -X1Y904D02* -X8Y904D01* -X2595Y904D02* -X2602Y904D01* -X1Y903D02* -X8Y903D01* -X2595Y903D02* -X2602Y903D01* -X1Y902D02* -X8Y902D01* -X2595Y902D02* -X2602Y902D01* -X1Y901D02* -X8Y901D01* -X2595Y901D02* -X2602Y901D01* -X1Y900D02* -X8Y900D01* -X2595Y900D02* -X2602Y900D01* -X1Y899D02* -X8Y899D01* -X2595Y899D02* -X2602Y899D01* -X1Y898D02* -X8Y898D01* -X2595Y898D02* -X2602Y898D01* -X1Y897D02* -X8Y897D01* -X2595Y897D02* -X2602Y897D01* -X1Y896D02* -X8Y896D01* -X2595Y896D02* -X2602Y896D01* -X1Y895D02* -X8Y895D01* -X2595Y895D02* -X2602Y895D01* -X1Y894D02* -X8Y894D01* -X2595Y894D02* -X2602Y894D01* -X1Y893D02* -X8Y893D01* -X2595Y893D02* -X2602Y893D01* -X1Y892D02* -X8Y892D01* -X2595Y892D02* -X2602Y892D01* -X1Y891D02* -X8Y891D01* -X2595Y891D02* -X2602Y891D01* -X1Y890D02* -X8Y890D01* -X2595Y890D02* -X2602Y890D01* -X1Y889D02* -X8Y889D01* -X2595Y889D02* -X2602Y889D01* -X1Y888D02* -X8Y888D01* -X2595Y888D02* -X2602Y888D01* -X1Y887D02* -X8Y887D01* -X2595Y887D02* -X2602Y887D01* -X1Y886D02* -X8Y886D01* -X2595Y886D02* -X2602Y886D01* -X1Y885D02* -X8Y885D01* -X2595Y885D02* -X2602Y885D01* -X1Y884D02* -X8Y884D01* -X2595Y884D02* -X2602Y884D01* -X1Y883D02* -X8Y883D01* -X2595Y883D02* -X2602Y883D01* -X1Y882D02* -X8Y882D01* -X2595Y882D02* -X2602Y882D01* -X1Y881D02* -X8Y881D01* -X2595Y881D02* -X2602Y881D01* -X1Y880D02* -X8Y880D01* -X2595Y880D02* -X2602Y880D01* -X1Y879D02* -X8Y879D01* -X2595Y879D02* -X2602Y879D01* -X1Y878D02* -X8Y878D01* -X2595Y878D02* -X2602Y878D01* -X1Y877D02* -X8Y877D01* -X2595Y877D02* -X2602Y877D01* -X1Y876D02* -X8Y876D01* -X2595Y876D02* -X2602Y876D01* -X1Y875D02* -X8Y875D01* -X2595Y875D02* -X2602Y875D01* -X1Y874D02* -X8Y874D01* -X2595Y874D02* -X2602Y874D01* -X1Y873D02* -X8Y873D01* -X2595Y873D02* -X2602Y873D01* -X1Y872D02* -X8Y872D01* -X2595Y872D02* -X2602Y872D01* -X1Y871D02* -X8Y871D01* -X2595Y871D02* -X2602Y871D01* -X1Y870D02* -X8Y870D01* -X2595Y870D02* -X2602Y870D01* -X1Y869D02* -X8Y869D01* -X2595Y869D02* -X2602Y869D01* -X1Y868D02* -X8Y868D01* -X2595Y868D02* -X2602Y868D01* -X1Y867D02* -X8Y867D01* -X2595Y867D02* -X2602Y867D01* -X1Y866D02* -X8Y866D01* -X2595Y866D02* -X2602Y866D01* -X1Y865D02* -X8Y865D01* -X2595Y865D02* -X2602Y865D01* -X1Y864D02* -X8Y864D01* -X2595Y864D02* -X2602Y864D01* -X1Y863D02* -X8Y863D01* -X2595Y863D02* -X2602Y863D01* -X1Y862D02* -X8Y862D01* -X2595Y862D02* -X2602Y862D01* -X1Y861D02* -X8Y861D01* -X2595Y861D02* -X2602Y861D01* -X1Y860D02* -X8Y860D01* -X2595Y860D02* -X2602Y860D01* -X1Y859D02* -X8Y859D01* -X2595Y859D02* -X2602Y859D01* -X1Y858D02* -X8Y858D01* -X2595Y858D02* -X2602Y858D01* -X1Y857D02* -X8Y857D01* -X2595Y857D02* -X2602Y857D01* -X1Y856D02* -X8Y856D01* -X2595Y856D02* -X2602Y856D01* -X1Y855D02* -X8Y855D01* -X2595Y855D02* -X2602Y855D01* -X1Y854D02* -X8Y854D01* -X2595Y854D02* -X2602Y854D01* -X1Y853D02* -X8Y853D01* -X2595Y853D02* -X2602Y853D01* -X1Y852D02* -X8Y852D01* -X2595Y852D02* -X2602Y852D01* -X1Y851D02* -X8Y851D01* -X2595Y851D02* -X2602Y851D01* -X1Y850D02* -X8Y850D01* -X2595Y850D02* -X2602Y850D01* -X1Y849D02* -X8Y849D01* -X2595Y849D02* -X2602Y849D01* -X1Y848D02* -X8Y848D01* -X2595Y848D02* -X2602Y848D01* -X1Y847D02* -X8Y847D01* -X2595Y847D02* -X2602Y847D01* -X1Y846D02* -X8Y846D01* -X2595Y846D02* -X2602Y846D01* -X1Y845D02* -X8Y845D01* -X2595Y845D02* -X2602Y845D01* -X1Y844D02* -X8Y844D01* -X2595Y844D02* -X2602Y844D01* -X1Y843D02* -X8Y843D01* -X2595Y843D02* -X2602Y843D01* -X1Y842D02* -X8Y842D01* -X2595Y842D02* -X2602Y842D01* -X1Y841D02* -X8Y841D01* -X2595Y841D02* -X2602Y841D01* -X1Y840D02* -X8Y840D01* -X2595Y840D02* -X2602Y840D01* -X1Y839D02* -X8Y839D01* -X2595Y839D02* -X2602Y839D01* -X1Y838D02* -X8Y838D01* -X2595Y838D02* -X2602Y838D01* -X1Y837D02* -X8Y837D01* -X2595Y837D02* -X2602Y837D01* -X1Y836D02* -X8Y836D01* -X2595Y836D02* -X2602Y836D01* -X1Y835D02* -X8Y835D01* -X2595Y835D02* -X2602Y835D01* -X1Y834D02* -X8Y834D01* -X2595Y834D02* -X2602Y834D01* -X1Y833D02* -X8Y833D01* -X2595Y833D02* -X2602Y833D01* -X1Y832D02* -X8Y832D01* -X2595Y832D02* -X2602Y832D01* -X1Y831D02* -X8Y831D01* -X2595Y831D02* -X2602Y831D01* -X1Y830D02* -X8Y830D01* -X2595Y830D02* -X2602Y830D01* -X1Y829D02* -X8Y829D01* -X2595Y829D02* -X2602Y829D01* -X1Y828D02* -X8Y828D01* -X2595Y828D02* -X2602Y828D01* -X1Y827D02* -X8Y827D01* -X2595Y827D02* -X2602Y827D01* -X1Y826D02* -X8Y826D01* -X2595Y826D02* -X2602Y826D01* -X1Y825D02* -X8Y825D01* -X2595Y825D02* -X2602Y825D01* -X1Y824D02* -X8Y824D01* -X2595Y824D02* -X2602Y824D01* -X1Y823D02* -X8Y823D01* -X2595Y823D02* -X2602Y823D01* -X1Y822D02* -X8Y822D01* -X2595Y822D02* -X2602Y822D01* -X1Y821D02* -X8Y821D01* -X2595Y821D02* -X2602Y821D01* -X1Y820D02* -X8Y820D01* -X2595Y820D02* -X2602Y820D01* -X1Y819D02* -X8Y819D01* -X2595Y819D02* -X2602Y819D01* -X1Y818D02* -X8Y818D01* -X2595Y818D02* -X2602Y818D01* -X1Y817D02* -X8Y817D01* -X2595Y817D02* -X2602Y817D01* -X1Y816D02* -X8Y816D01* -X2595Y816D02* -X2602Y816D01* -X1Y815D02* -X8Y815D01* -X2595Y815D02* -X2602Y815D01* -X1Y814D02* -X8Y814D01* -X2595Y814D02* -X2602Y814D01* -X1Y813D02* -X8Y813D01* -X2595Y813D02* -X2602Y813D01* -X1Y812D02* -X8Y812D01* -X2595Y812D02* -X2602Y812D01* -X1Y811D02* -X8Y811D01* -X2595Y811D02* -X2602Y811D01* -X1Y810D02* -X8Y810D01* -X2595Y810D02* -X2602Y810D01* -X1Y809D02* -X8Y809D01* -X2595Y809D02* -X2602Y809D01* -X1Y808D02* -X8Y808D01* -X2595Y808D02* -X2602Y808D01* -X1Y807D02* -X8Y807D01* -X2595Y807D02* -X2602Y807D01* -X1Y806D02* -X8Y806D01* -X2595Y806D02* -X2602Y806D01* -X1Y805D02* -X8Y805D01* -X2595Y805D02* -X2602Y805D01* -X1Y804D02* -X8Y804D01* -X2595Y804D02* -X2602Y804D01* -X1Y803D02* -X8Y803D01* -X2595Y803D02* -X2602Y803D01* -X1Y802D02* -X8Y802D01* -X2595Y802D02* -X2602Y802D01* -X1Y801D02* -X8Y801D01* -X2595Y801D02* -X2602Y801D01* -X1Y800D02* -X8Y800D01* -X2595Y800D02* -X2602Y800D01* -X1Y799D02* -X8Y799D01* -X2595Y799D02* -X2602Y799D01* -X1Y798D02* -X8Y798D01* -X2595Y798D02* -X2602Y798D01* -X1Y797D02* -X8Y797D01* -X2595Y797D02* -X2602Y797D01* -X1Y796D02* -X8Y796D01* -X2595Y796D02* -X2602Y796D01* -X1Y795D02* -X8Y795D01* -X2595Y795D02* -X2602Y795D01* -X1Y794D02* -X8Y794D01* -X2595Y794D02* -X2602Y794D01* -X1Y793D02* -X8Y793D01* -X2595Y793D02* -X2602Y793D01* -X1Y792D02* -X8Y792D01* -X2595Y792D02* -X2602Y792D01* -X1Y791D02* -X8Y791D01* -X2595Y791D02* -X2602Y791D01* -X1Y790D02* -X8Y790D01* -X2595Y790D02* -X2602Y790D01* -X1Y789D02* -X8Y789D01* -X2595Y789D02* -X2602Y789D01* -X1Y788D02* -X8Y788D01* -X2595Y788D02* -X2602Y788D01* -X1Y787D02* -X8Y787D01* -X2595Y787D02* -X2602Y787D01* -X1Y786D02* -X8Y786D01* -X2595Y786D02* -X2602Y786D01* -X1Y785D02* -X8Y785D01* -X2595Y785D02* -X2602Y785D01* -X1Y784D02* -X8Y784D01* -X2595Y784D02* -X2602Y784D01* -X1Y783D02* -X8Y783D01* -X2595Y783D02* -X2602Y783D01* -X1Y782D02* -X8Y782D01* -X2595Y782D02* -X2602Y782D01* -X1Y781D02* -X8Y781D01* -X2595Y781D02* -X2602Y781D01* -X1Y780D02* -X8Y780D01* -X2595Y780D02* -X2602Y780D01* -X1Y779D02* -X8Y779D01* -X2595Y779D02* -X2602Y779D01* -X1Y778D02* -X8Y778D01* -X2595Y778D02* -X2602Y778D01* -X1Y777D02* -X8Y777D01* -X2595Y777D02* -X2602Y777D01* -X1Y776D02* -X8Y776D01* -X2595Y776D02* -X2602Y776D01* -X1Y775D02* -X8Y775D01* -X2595Y775D02* -X2602Y775D01* -X1Y774D02* -X8Y774D01* -X2595Y774D02* -X2602Y774D01* -X1Y773D02* -X8Y773D01* -X2595Y773D02* -X2602Y773D01* -X1Y772D02* -X8Y772D01* -X2595Y772D02* -X2602Y772D01* -X1Y771D02* -X8Y771D01* -X2595Y771D02* -X2602Y771D01* -X1Y770D02* -X8Y770D01* -X2595Y770D02* -X2602Y770D01* -X1Y769D02* -X8Y769D01* -X2595Y769D02* -X2602Y769D01* -X1Y768D02* -X8Y768D01* -X2595Y768D02* -X2602Y768D01* -X1Y767D02* -X8Y767D01* -X2595Y767D02* -X2602Y767D01* -X1Y766D02* -X8Y766D01* -X2595Y766D02* -X2602Y766D01* -X1Y765D02* -X8Y765D01* -X2595Y765D02* -X2602Y765D01* -X1Y764D02* -X8Y764D01* -X2595Y764D02* -X2602Y764D01* -X1Y763D02* -X8Y763D01* -X2595Y763D02* -X2602Y763D01* -X1Y762D02* -X8Y762D01* -X2595Y762D02* -X2602Y762D01* -X1Y761D02* -X8Y761D01* -X2595Y761D02* -X2602Y761D01* -X1Y760D02* -X8Y760D01* -X2595Y760D02* -X2602Y760D01* -X1Y759D02* -X8Y759D01* -X2595Y759D02* -X2602Y759D01* -X1Y758D02* -X8Y758D01* -X2595Y758D02* -X2602Y758D01* -X1Y757D02* -X8Y757D01* -X2595Y757D02* -X2602Y757D01* -X1Y756D02* -X8Y756D01* -X2595Y756D02* -X2602Y756D01* -X1Y755D02* -X8Y755D01* -X2595Y755D02* -X2602Y755D01* -X1Y754D02* -X8Y754D01* -X2595Y754D02* -X2602Y754D01* -X1Y753D02* -X8Y753D01* -X2595Y753D02* -X2602Y753D01* -X1Y752D02* -X8Y752D01* -X2595Y752D02* -X2602Y752D01* -X1Y751D02* -X8Y751D01* -X2595Y751D02* -X2602Y751D01* -X1Y750D02* -X8Y750D01* -X2595Y750D02* -X2602Y750D01* -X1Y749D02* -X8Y749D01* -X2595Y749D02* -X2602Y749D01* -X1Y748D02* -X8Y748D01* -X2595Y748D02* -X2602Y748D01* -X1Y747D02* -X8Y747D01* -X2595Y747D02* -X2602Y747D01* -X1Y746D02* -X8Y746D01* -X2595Y746D02* -X2602Y746D01* -X1Y745D02* -X8Y745D01* -X2595Y745D02* -X2602Y745D01* -X1Y744D02* -X8Y744D01* -X2595Y744D02* -X2602Y744D01* -X1Y743D02* -X8Y743D01* -X2595Y743D02* -X2602Y743D01* -X1Y742D02* -X8Y742D01* -X2595Y742D02* -X2602Y742D01* -X1Y741D02* -X8Y741D01* -X2595Y741D02* -X2602Y741D01* -X1Y740D02* -X8Y740D01* -X2595Y740D02* -X2602Y740D01* -X1Y739D02* -X8Y739D01* -X2595Y739D02* -X2602Y739D01* -X1Y738D02* -X8Y738D01* -X2595Y738D02* -X2602Y738D01* -X1Y737D02* -X8Y737D01* -X2595Y737D02* -X2602Y737D01* -X1Y736D02* -X8Y736D01* -X2595Y736D02* -X2602Y736D01* -X1Y735D02* -X8Y735D01* -X2595Y735D02* -X2602Y735D01* -X1Y734D02* -X8Y734D01* -X2595Y734D02* -X2602Y734D01* -X1Y733D02* -X8Y733D01* -X2595Y733D02* -X2602Y733D01* -X1Y732D02* -X8Y732D01* -X2595Y732D02* -X2602Y732D01* -X1Y731D02* -X8Y731D01* -X2595Y731D02* -X2602Y731D01* -X1Y730D02* -X8Y730D01* -X2595Y730D02* -X2602Y730D01* -X1Y729D02* -X8Y729D01* -X2595Y729D02* -X2602Y729D01* -X1Y728D02* -X8Y728D01* -X2595Y728D02* -X2602Y728D01* -X1Y727D02* -X8Y727D01* -X2595Y727D02* -X2602Y727D01* -X1Y726D02* -X8Y726D01* -X2595Y726D02* -X2602Y726D01* -X1Y725D02* -X8Y725D01* -X2595Y725D02* -X2602Y725D01* -X1Y724D02* -X8Y724D01* -X2595Y724D02* -X2602Y724D01* -X1Y723D02* -X8Y723D01* -X2595Y723D02* -X2602Y723D01* -X1Y722D02* -X8Y722D01* -X2595Y722D02* -X2602Y722D01* -X1Y721D02* -X8Y721D01* -X2595Y721D02* -X2602Y721D01* -X1Y720D02* -X8Y720D01* -X2595Y720D02* -X2602Y720D01* -X1Y719D02* -X8Y719D01* -X2595Y719D02* -X2602Y719D01* -X1Y718D02* -X8Y718D01* -X2595Y718D02* -X2602Y718D01* -X1Y717D02* -X8Y717D01* -X2595Y717D02* -X2602Y717D01* -X1Y716D02* -X8Y716D01* -X2595Y716D02* -X2602Y716D01* -X1Y715D02* -X8Y715D01* -X2595Y715D02* -X2602Y715D01* -X1Y714D02* -X8Y714D01* -X2595Y714D02* -X2602Y714D01* -X1Y713D02* -X8Y713D01* -X2595Y713D02* -X2602Y713D01* -X1Y712D02* -X8Y712D01* -X2595Y712D02* -X2602Y712D01* -X1Y711D02* -X8Y711D01* -X2595Y711D02* -X2602Y711D01* -X1Y710D02* -X8Y710D01* -X2595Y710D02* -X2602Y710D01* -X1Y709D02* -X8Y709D01* -X2595Y709D02* -X2602Y709D01* -X1Y708D02* -X8Y708D01* -X2595Y708D02* -X2602Y708D01* -X1Y707D02* -X8Y707D01* -X2595Y707D02* -X2602Y707D01* -X1Y706D02* -X8Y706D01* -X2595Y706D02* -X2602Y706D01* -X1Y705D02* -X8Y705D01* -X2595Y705D02* -X2602Y705D01* -X1Y704D02* -X8Y704D01* -X2595Y704D02* -X2602Y704D01* -X1Y703D02* -X8Y703D01* -X2595Y703D02* -X2602Y703D01* -X1Y702D02* -X8Y702D01* -X2595Y702D02* -X2602Y702D01* -X1Y701D02* -X8Y701D01* -X2595Y701D02* -X2602Y701D01* -X1Y700D02* -X8Y700D01* -X2595Y700D02* -X2602Y700D01* -X1Y699D02* -X8Y699D01* -X2595Y699D02* -X2602Y699D01* -X1Y698D02* -X8Y698D01* -X2595Y698D02* -X2602Y698D01* -X1Y697D02* -X8Y697D01* -X2595Y697D02* -X2602Y697D01* -X1Y696D02* -X8Y696D01* -X2595Y696D02* -X2602Y696D01* -X1Y695D02* -X8Y695D01* -X2595Y695D02* -X2602Y695D01* -X1Y694D02* -X8Y694D01* -X2595Y694D02* -X2602Y694D01* -X1Y693D02* -X8Y693D01* -X2595Y693D02* -X2602Y693D01* -X1Y692D02* -X8Y692D01* -X2595Y692D02* -X2602Y692D01* -X1Y691D02* -X8Y691D01* -X2595Y691D02* -X2602Y691D01* -X1Y690D02* -X8Y690D01* -X2595Y690D02* -X2602Y690D01* -X1Y689D02* -X8Y689D01* -X2595Y689D02* -X2602Y689D01* -X1Y688D02* -X8Y688D01* -X2595Y688D02* -X2602Y688D01* -X1Y687D02* -X8Y687D01* -X2595Y687D02* -X2602Y687D01* -X1Y686D02* -X8Y686D01* -X2595Y686D02* -X2602Y686D01* -X1Y685D02* -X8Y685D01* -X2595Y685D02* -X2602Y685D01* -X1Y684D02* -X8Y684D01* -X2595Y684D02* -X2602Y684D01* -X1Y683D02* -X8Y683D01* -X2595Y683D02* -X2602Y683D01* -X1Y682D02* -X8Y682D01* -X2595Y682D02* -X2602Y682D01* -X1Y681D02* -X8Y681D01* -X2595Y681D02* -X2602Y681D01* -X1Y680D02* -X8Y680D01* -X2595Y680D02* -X2602Y680D01* -X1Y679D02* -X8Y679D01* -X2595Y679D02* -X2602Y679D01* -X1Y678D02* -X8Y678D01* -X2595Y678D02* -X2602Y678D01* -X1Y677D02* -X8Y677D01* -X2595Y677D02* -X2602Y677D01* -X1Y676D02* -X8Y676D01* -X2595Y676D02* -X2602Y676D01* -X1Y675D02* -X8Y675D01* -X2595Y675D02* -X2602Y675D01* -X1Y674D02* -X8Y674D01* -X2595Y674D02* -X2602Y674D01* -X1Y673D02* -X8Y673D01* -X2595Y673D02* -X2602Y673D01* -X1Y672D02* -X8Y672D01* -X2595Y672D02* -X2602Y672D01* -X1Y671D02* -X8Y671D01* -X2595Y671D02* -X2602Y671D01* -X1Y670D02* -X8Y670D01* -X2595Y670D02* -X2602Y670D01* -X1Y669D02* -X8Y669D01* -X2595Y669D02* -X2602Y669D01* -X1Y668D02* -X8Y668D01* -X2595Y668D02* -X2602Y668D01* -X1Y667D02* -X8Y667D01* -X2595Y667D02* -X2602Y667D01* -X1Y666D02* -X8Y666D01* -X2595Y666D02* -X2602Y666D01* -X1Y665D02* -X8Y665D01* -X2595Y665D02* -X2602Y665D01* -X1Y664D02* -X8Y664D01* -X2595Y664D02* -X2602Y664D01* -X1Y663D02* -X8Y663D01* -X2595Y663D02* -X2602Y663D01* -X1Y662D02* -X8Y662D01* -X2595Y662D02* -X2602Y662D01* -X1Y661D02* -X8Y661D01* -X2595Y661D02* -X2602Y661D01* -X1Y660D02* -X8Y660D01* -X2595Y660D02* -X2602Y660D01* -X1Y659D02* -X8Y659D01* -X2595Y659D02* -X2602Y659D01* -X1Y658D02* -X8Y658D01* -X2595Y658D02* -X2602Y658D01* -X1Y657D02* -X8Y657D01* -X2595Y657D02* -X2602Y657D01* -X1Y656D02* -X8Y656D01* -X2595Y656D02* -X2602Y656D01* -X1Y655D02* -X8Y655D01* -X2595Y655D02* -X2602Y655D01* -X1Y654D02* -X8Y654D01* -X2595Y654D02* -X2602Y654D01* -X1Y653D02* -X8Y653D01* -X2595Y653D02* -X2602Y653D01* -X1Y652D02* -X8Y652D01* -X2595Y652D02* -X2602Y652D01* -X1Y651D02* -X8Y651D01* -X2595Y651D02* -X2602Y651D01* -X1Y650D02* -X8Y650D01* -X2595Y650D02* -X2602Y650D01* -X1Y649D02* -X8Y649D01* -X2595Y649D02* -X2602Y649D01* -X1Y648D02* -X8Y648D01* -X2595Y648D02* -X2602Y648D01* -X1Y647D02* -X8Y647D01* -X2595Y647D02* -X2602Y647D01* -X1Y646D02* -X8Y646D01* -X2595Y646D02* -X2602Y646D01* -X1Y645D02* -X8Y645D01* -X2595Y645D02* -X2602Y645D01* -X1Y644D02* -X8Y644D01* -X2595Y644D02* -X2602Y644D01* -X1Y643D02* -X8Y643D01* -X2595Y643D02* -X2602Y643D01* -X1Y642D02* -X8Y642D01* -X2595Y642D02* -X2602Y642D01* -X1Y641D02* -X8Y641D01* -X2595Y641D02* -X2602Y641D01* -X1Y640D02* -X8Y640D01* -X2595Y640D02* -X2602Y640D01* -X1Y639D02* -X8Y639D01* -X2595Y639D02* -X2602Y639D01* -X1Y638D02* -X8Y638D01* -X2595Y638D02* -X2602Y638D01* -X1Y637D02* -X8Y637D01* -X2595Y637D02* -X2602Y637D01* -X1Y636D02* -X8Y636D01* -X2595Y636D02* -X2602Y636D01* -X1Y635D02* -X8Y635D01* -X2595Y635D02* -X2602Y635D01* -X1Y634D02* -X8Y634D01* -X2595Y634D02* -X2602Y634D01* -X1Y633D02* -X8Y633D01* -X2595Y633D02* -X2602Y633D01* -X1Y632D02* -X8Y632D01* -X2595Y632D02* -X2602Y632D01* -X1Y631D02* -X8Y631D01* -X2595Y631D02* -X2602Y631D01* -X1Y630D02* -X8Y630D01* -X2595Y630D02* -X2602Y630D01* -X1Y629D02* -X8Y629D01* -X2595Y629D02* -X2602Y629D01* -X1Y628D02* -X8Y628D01* -X2595Y628D02* -X2602Y628D01* -X1Y627D02* -X8Y627D01* -X2595Y627D02* -X2602Y627D01* -X1Y626D02* -X8Y626D01* -X2595Y626D02* -X2602Y626D01* -X1Y625D02* -X8Y625D01* -X2595Y625D02* -X2602Y625D01* -X1Y624D02* -X8Y624D01* -X2595Y624D02* -X2602Y624D01* -X1Y623D02* -X8Y623D01* -X2595Y623D02* -X2602Y623D01* -X1Y622D02* -X8Y622D01* -X2595Y622D02* -X2602Y622D01* -X1Y621D02* -X8Y621D01* -X2595Y621D02* -X2602Y621D01* -X1Y620D02* -X8Y620D01* -X2595Y620D02* -X2602Y620D01* -X1Y619D02* -X8Y619D01* -X2595Y619D02* -X2602Y619D01* -X1Y618D02* -X8Y618D01* -X2595Y618D02* -X2602Y618D01* -X1Y617D02* -X8Y617D01* -X2595Y617D02* -X2602Y617D01* -X1Y616D02* -X8Y616D01* -X2595Y616D02* -X2602Y616D01* -X1Y615D02* -X8Y615D01* -X2595Y615D02* -X2602Y615D01* -X1Y614D02* -X8Y614D01* -X2595Y614D02* -X2602Y614D01* -X1Y613D02* -X8Y613D01* -X2595Y613D02* -X2602Y613D01* -X1Y612D02* -X8Y612D01* -X2595Y612D02* -X2602Y612D01* -X1Y611D02* -X8Y611D01* -X2595Y611D02* -X2602Y611D01* -X1Y610D02* -X8Y610D01* -X2595Y610D02* -X2602Y610D01* -X1Y609D02* -X8Y609D01* -X2595Y609D02* -X2602Y609D01* -X1Y608D02* -X8Y608D01* -X2595Y608D02* -X2602Y608D01* -X1Y607D02* -X8Y607D01* -X2595Y607D02* -X2602Y607D01* -X1Y606D02* -X8Y606D01* -X2595Y606D02* -X2602Y606D01* -X1Y605D02* -X8Y605D01* -X2595Y605D02* -X2602Y605D01* -X1Y604D02* -X8Y604D01* -X2595Y604D02* -X2602Y604D01* -X1Y603D02* -X8Y603D01* -X2595Y603D02* -X2602Y603D01* -X1Y602D02* -X8Y602D01* -X2595Y602D02* -X2602Y602D01* -X1Y601D02* -X8Y601D01* -X2595Y601D02* -X2602Y601D01* -X1Y600D02* -X8Y600D01* -X2595Y600D02* -X2602Y600D01* -X1Y599D02* -X8Y599D01* -X2595Y599D02* -X2602Y599D01* -X1Y598D02* -X8Y598D01* -X2595Y598D02* -X2602Y598D01* -X1Y597D02* -X8Y597D01* -X2595Y597D02* -X2602Y597D01* -X1Y596D02* -X8Y596D01* -X2595Y596D02* -X2602Y596D01* -X1Y595D02* -X8Y595D01* -X2595Y595D02* -X2602Y595D01* -X1Y594D02* -X8Y594D01* -X2595Y594D02* -X2602Y594D01* -X1Y593D02* -X8Y593D01* -X2595Y593D02* -X2602Y593D01* -X1Y592D02* -X8Y592D01* -X2595Y592D02* -X2602Y592D01* -X1Y591D02* -X8Y591D01* -X2595Y591D02* -X2602Y591D01* -X1Y590D02* -X8Y590D01* -X2595Y590D02* -X2602Y590D01* -X1Y589D02* -X8Y589D01* -X2595Y589D02* -X2602Y589D01* -X1Y588D02* -X8Y588D01* -X2595Y588D02* -X2602Y588D01* -X1Y587D02* -X8Y587D01* -X2595Y587D02* -X2602Y587D01* -X1Y586D02* -X8Y586D01* -X2595Y586D02* -X2602Y586D01* -X1Y585D02* -X8Y585D01* -X2595Y585D02* -X2602Y585D01* -X1Y584D02* -X8Y584D01* -X2595Y584D02* -X2602Y584D01* -X1Y583D02* -X8Y583D01* -X2595Y583D02* -X2602Y583D01* -X1Y582D02* -X8Y582D01* -X2595Y582D02* -X2602Y582D01* -X1Y581D02* -X8Y581D01* -X2595Y581D02* -X2602Y581D01* -X1Y580D02* -X8Y580D01* -X2595Y580D02* -X2602Y580D01* -X1Y579D02* -X8Y579D01* -X2595Y579D02* -X2602Y579D01* -X1Y578D02* -X8Y578D01* -X2595Y578D02* -X2602Y578D01* -X1Y577D02* -X8Y577D01* -X2595Y577D02* -X2602Y577D01* -X1Y576D02* -X8Y576D01* -X2595Y576D02* -X2602Y576D01* -X1Y575D02* -X8Y575D01* -X2595Y575D02* -X2602Y575D01* -X1Y574D02* -X8Y574D01* -X2595Y574D02* -X2602Y574D01* -X1Y573D02* -X8Y573D01* -X2595Y573D02* -X2602Y573D01* -X1Y572D02* -X8Y572D01* -X2595Y572D02* -X2602Y572D01* -X1Y571D02* -X8Y571D01* -X2595Y571D02* -X2602Y571D01* -X1Y570D02* -X8Y570D01* -X2595Y570D02* -X2602Y570D01* -X1Y569D02* -X8Y569D01* -X2595Y569D02* -X2602Y569D01* -X1Y568D02* -X8Y568D01* -X2595Y568D02* -X2602Y568D01* -X1Y567D02* -X8Y567D01* -X2595Y567D02* -X2602Y567D01* -X1Y566D02* -X8Y566D01* -X2595Y566D02* -X2602Y566D01* -X1Y565D02* -X8Y565D01* -X2595Y565D02* -X2602Y565D01* -X1Y564D02* -X8Y564D01* -X2595Y564D02* -X2602Y564D01* -X1Y563D02* -X8Y563D01* -X2595Y563D02* -X2602Y563D01* -X1Y562D02* -X8Y562D01* -X2595Y562D02* -X2602Y562D01* -X1Y561D02* -X8Y561D01* -X2595Y561D02* -X2602Y561D01* -X1Y560D02* -X8Y560D01* -X2595Y560D02* -X2602Y560D01* -X1Y559D02* -X8Y559D01* -X2595Y559D02* -X2602Y559D01* -X1Y558D02* -X8Y558D01* -X2595Y558D02* -X2602Y558D01* -X1Y557D02* -X8Y557D01* -X2595Y557D02* -X2602Y557D01* -X1Y556D02* -X8Y556D01* -X2595Y556D02* -X2602Y556D01* -X1Y555D02* -X8Y555D01* -X2595Y555D02* -X2602Y555D01* -X1Y554D02* -X8Y554D01* -X2595Y554D02* -X2602Y554D01* -X1Y553D02* -X8Y553D01* -X2595Y553D02* -X2602Y553D01* -X1Y552D02* -X8Y552D01* -X2595Y552D02* -X2602Y552D01* -X1Y551D02* -X8Y551D01* -X2595Y551D02* -X2602Y551D01* -X1Y550D02* -X8Y550D01* -X2595Y550D02* -X2602Y550D01* -X1Y549D02* -X8Y549D01* -X2595Y549D02* -X2602Y549D01* -X1Y548D02* -X8Y548D01* -X2595Y548D02* -X2602Y548D01* -X1Y547D02* -X8Y547D01* -X2595Y547D02* -X2602Y547D01* -X1Y546D02* -X8Y546D01* -X2595Y546D02* -X2602Y546D01* -X1Y545D02* -X8Y545D01* -X2595Y545D02* -X2602Y545D01* -X1Y544D02* -X8Y544D01* -X2595Y544D02* -X2602Y544D01* -X1Y543D02* -X8Y543D01* -X2595Y543D02* -X2602Y543D01* -X1Y542D02* -X8Y542D01* -X2595Y542D02* -X2602Y542D01* -X1Y541D02* -X8Y541D01* -X2595Y541D02* -X2602Y541D01* -X1Y540D02* -X8Y540D01* -X2595Y540D02* -X2602Y540D01* -X1Y539D02* -X8Y539D01* -X2595Y539D02* -X2602Y539D01* -X1Y538D02* -X8Y538D01* -X2595Y538D02* -X2602Y538D01* -X1Y537D02* -X8Y537D01* -X2595Y537D02* -X2602Y537D01* -X1Y536D02* -X8Y536D01* -X2595Y536D02* -X2602Y536D01* -X1Y535D02* -X8Y535D01* -X2595Y535D02* -X2602Y535D01* -X1Y534D02* -X8Y534D01* -X2595Y534D02* -X2602Y534D01* -X1Y533D02* -X8Y533D01* -X2595Y533D02* -X2602Y533D01* -X1Y532D02* -X8Y532D01* -X216Y532D02* -X256Y532D01* -X349Y532D02* -X376Y532D01* -X405Y532D02* -X448Y532D01* -X487Y532D02* -X492Y532D01* -X531Y532D02* -X564Y532D01* -X821Y532D02* -X823Y532D01* -X916Y532D02* -X932Y532D01* -X2595Y532D02* -X2602Y532D01* -X1Y531D02* -X8Y531D01* -X216Y531D02* -X257Y531D01* -X347Y531D02* -X378Y531D01* -X405Y531D02* -X448Y531D01* -X484Y531D02* -X494Y531D01* -X531Y531D02* -X566Y531D01* -X819Y531D02* -X825Y531D01* -X915Y531D02* -X933Y531D01* -X2595Y531D02* -X2602Y531D01* -X1Y530D02* -X8Y530D01* -X216Y530D02* -X258Y530D01* -X345Y530D02* -X380Y530D01* -X405Y530D02* -X448Y530D01* -X483Y530D02* -X496Y530D01* -X531Y530D02* -X568Y530D01* -X819Y530D02* -X825Y530D01* -X914Y530D02* -X934Y530D01* -X2595Y530D02* -X2602Y530D01* -X1Y529D02* -X8Y529D01* -X216Y529D02* -X258Y529D01* -X344Y529D02* -X381Y529D01* -X405Y529D02* -X448Y529D01* -X482Y529D02* -X497Y529D01* -X531Y529D02* -X569Y529D01* -X818Y529D02* -X826Y529D01* -X914Y529D02* -X934Y529D01* -X2595Y529D02* -X2602Y529D01* -X1Y528D02* -X8Y528D01* -X216Y528D02* -X258Y528D01* -X344Y528D02* -X382Y528D01* -X405Y528D02* -X448Y528D01* -X481Y528D02* -X498Y528D01* -X531Y528D02* -X570Y528D01* -X818Y528D02* -X826Y528D01* -X914Y528D02* -X935Y528D01* -X2595Y528D02* -X2602Y528D01* -X1Y527D02* -X8Y527D01* -X216Y527D02* -X258Y527D01* -X343Y527D02* -X383Y527D01* -X405Y527D02* -X448Y527D01* -X480Y527D02* -X498Y527D01* -X531Y527D02* -X571Y527D01* -X818Y527D02* -X826Y527D01* -X914Y527D02* -X935Y527D01* -X2595Y527D02* -X2602Y527D01* -X1Y526D02* -X8Y526D01* -X216Y526D02* -X258Y526D01* -X342Y526D02* -X383Y526D01* -X405Y526D02* -X448Y526D01* -X479Y526D02* -X499Y526D01* -X531Y526D02* -X572Y526D01* -X818Y526D02* -X826Y526D01* -X914Y526D02* -X935Y526D01* -X2595Y526D02* -X2602Y526D01* -X1Y525D02* -X8Y525D01* -X216Y525D02* -X257Y525D01* -X342Y525D02* -X384Y525D01* -X405Y525D02* -X448Y525D01* -X479Y525D02* -X500Y525D01* -X531Y525D02* -X572Y525D01* -X818Y525D02* -X826Y525D01* -X915Y525D02* -X935Y525D01* -X2595Y525D02* -X2602Y525D01* -X1Y524D02* -X8Y524D01* -X216Y524D02* -X256Y524D01* -X342Y524D02* -X384Y524D01* -X405Y524D02* -X448Y524D01* -X478Y524D02* -X500Y524D01* -X531Y524D02* -X573Y524D01* -X818Y524D02* -X826Y524D01* -X916Y524D02* -X935Y524D01* -X2595Y524D02* -X2602Y524D01* -X1Y523D02* -X8Y523D01* -X216Y523D02* -X224Y523D01* -X342Y523D02* -X350Y523D01* -X375Y523D02* -X384Y523D01* -X405Y523D02* -X413Y523D01* -X422Y523D02* -X430Y523D01* -X440Y523D02* -X448Y523D01* -X478Y523D02* -X487Y523D01* -X491Y523D02* -X501Y523D01* -X531Y523D02* -X539Y523D01* -X563Y523D02* -X573Y523D01* -X818Y523D02* -X826Y523D01* -X927Y523D02* -X935Y523D01* -X2595Y523D02* -X2602Y523D01* -X1Y522D02* -X8Y522D01* -X216Y522D02* -X224Y522D01* -X342Y522D02* -X350Y522D01* -X376Y522D02* -X384Y522D01* -X405Y522D02* -X413Y522D01* -X422Y522D02* -X430Y522D01* -X440Y522D02* -X448Y522D01* -X477Y522D02* -X486Y522D01* -X492Y522D02* -X501Y522D01* -X531Y522D02* -X539Y522D01* -X565Y522D02* -X573Y522D01* -X818Y522D02* -X826Y522D01* -X927Y522D02* -X935Y522D01* -X2595Y522D02* -X2602Y522D01* -X1Y521D02* -X8Y521D01* -X216Y521D02* -X224Y521D01* -X342Y521D02* -X351Y521D01* -X377Y521D02* -X384Y521D01* -X405Y521D02* -X413Y521D01* -X422Y521D02* -X430Y521D01* -X440Y521D02* -X448Y521D01* -X477Y521D02* -X486Y521D01* -X493Y521D02* -X502Y521D01* -X531Y521D02* -X539Y521D01* -X565Y521D02* -X574Y521D01* -X818Y521D02* -X826Y521D01* -X927Y521D02* -X935Y521D01* -X2595Y521D02* -X2602Y521D01* -X1Y520D02* -X8Y520D01* -X216Y520D02* -X224Y520D01* -X342Y520D02* -X351Y520D01* -X377Y520D02* -X384Y520D01* -X405Y520D02* -X413Y520D01* -X422Y520D02* -X430Y520D01* -X440Y520D02* -X447Y520D01* -X476Y520D02* -X485Y520D01* -X493Y520D02* -X502Y520D01* -X531Y520D02* -X539Y520D01* -X566Y520D02* -X574Y520D01* -X818Y520D02* -X826Y520D01* -X927Y520D02* -X935Y520D01* -X2595Y520D02* -X2602Y520D01* -X1Y519D02* -X8Y519D01* -X216Y519D02* -X224Y519D01* -X342Y519D02* -X352Y519D01* -X377Y519D02* -X384Y519D01* -X405Y519D02* -X412Y519D01* -X422Y519D02* -X430Y519D01* -X440Y519D02* -X447Y519D01* -X476Y519D02* -X485Y519D01* -X494Y519D02* -X503Y519D01* -X531Y519D02* -X539Y519D01* -X566Y519D02* -X574Y519D01* -X818Y519D02* -X826Y519D01* -X927Y519D02* -X935Y519D01* -X2595Y519D02* -X2602Y519D01* -X1Y518D02* -X8Y518D01* -X216Y518D02* -X224Y518D01* -X343Y518D02* -X353Y518D01* -X378Y518D02* -X384Y518D01* -X406Y518D02* -X412Y518D01* -X422Y518D02* -X430Y518D01* -X441Y518D02* -X447Y518D01* -X475Y518D02* -X484Y518D01* -X494Y518D02* -X503Y518D01* -X531Y518D02* -X539Y518D01* -X566Y518D02* -X574Y518D01* -X818Y518D02* -X826Y518D01* -X927Y518D02* -X935Y518D01* -X2595Y518D02* -X2602Y518D01* -X1Y517D02* -X8Y517D01* -X216Y517D02* -X224Y517D01* -X343Y517D02* -X354Y517D01* -X379Y517D02* -X383Y517D01* -X407Y517D02* -X411Y517D01* -X422Y517D02* -X430Y517D01* -X442Y517D02* -X446Y517D01* -X475Y517D02* -X484Y517D01* -X495Y517D02* -X504Y517D01* -X531Y517D02* -X539Y517D01* -X566Y517D02* -X574Y517D01* -X818Y517D02* -X826Y517D01* -X927Y517D02* -X935Y517D01* -X2595Y517D02* -X2602Y517D01* -X1Y516D02* -X8Y516D01* -X216Y516D02* -X224Y516D01* -X344Y516D02* -X354Y516D01* -X422Y516D02* -X430Y516D01* -X474Y516D02* -X483Y516D01* -X495Y516D02* -X504Y516D01* -X531Y516D02* -X539Y516D01* -X566Y516D02* -X574Y516D01* -X818Y516D02* -X826Y516D01* -X927Y516D02* -X935Y516D01* -X2595Y516D02* -X2602Y516D01* -X1Y515D02* -X8Y515D01* -X216Y515D02* -X224Y515D01* -X345Y515D02* -X355Y515D01* -X422Y515D02* -X430Y515D01* -X474Y515D02* -X483Y515D01* -X496Y515D02* -X505Y515D01* -X531Y515D02* -X539Y515D01* -X566Y515D02* -X574Y515D01* -X818Y515D02* -X826Y515D01* -X927Y515D02* -X935Y515D01* -X2595Y515D02* -X2602Y515D01* -X1Y514D02* -X8Y514D01* -X216Y514D02* -X224Y514D01* -X346Y514D02* -X356Y514D01* -X422Y514D02* -X430Y514D01* -X473Y514D02* -X482Y514D01* -X496Y514D02* -X505Y514D01* -X531Y514D02* -X539Y514D01* -X566Y514D02* -X574Y514D01* -X818Y514D02* -X826Y514D01* -X927Y514D02* -X935Y514D01* -X2595Y514D02* -X2602Y514D01* -X1Y513D02* -X8Y513D01* -X216Y513D02* -X224Y513D01* -X346Y513D02* -X357Y513D01* -X422Y513D02* -X430Y513D01* -X473Y513D02* -X482Y513D01* -X497Y513D02* -X506Y513D01* -X531Y513D02* -X539Y513D01* -X566Y513D02* -X574Y513D01* -X658Y513D02* -X662Y513D01* -X669Y513D02* -X676Y513D01* -X686Y513D02* -X692Y513D01* -X732Y513D02* -X751Y513D01* -X795Y513D02* -X810Y513D01* -X818Y513D02* -X826Y513D01* -X848Y513D02* -X852Y513D01* -X883Y513D02* -X887Y513D01* -X927Y513D02* -X935Y513D01* -X984Y513D02* -X1003Y513D01* -X2595Y513D02* -X2602Y513D01* -X1Y512D02* -X8Y512D01* -X216Y512D02* -X224Y512D01* -X347Y512D02* -X358Y512D01* -X422Y512D02* -X430Y512D01* -X472Y512D02* -X481Y512D01* -X497Y512D02* -X506Y512D01* -X531Y512D02* -X539Y512D01* -X566Y512D02* -X574Y512D01* -X657Y512D02* -X663Y512D01* -X667Y512D02* -X678Y512D01* -X684Y512D02* -X694Y512D01* -X730Y512D02* -X753Y512D01* -X793Y512D02* -X812Y512D01* -X818Y512D02* -X826Y512D01* -X847Y512D02* -X853Y512D01* -X882Y512D02* -X888Y512D01* -X927Y512D02* -X935Y512D01* -X982Y512D02* -X1005Y512D01* -X2595Y512D02* -X2602Y512D01* -X1Y511D02* -X8Y511D01* -X216Y511D02* -X224Y511D01* -X348Y511D02* -X358Y511D01* -X422Y511D02* -X430Y511D01* -X472Y511D02* -X481Y511D01* -X498Y511D02* -X507Y511D01* -X531Y511D02* -X539Y511D01* -X566Y511D02* -X574Y511D01* -X657Y511D02* -X679Y511D01* -X683Y511D02* -X695Y511D01* -X728Y511D02* -X755Y511D01* -X792Y511D02* -X813Y511D01* -X818Y511D02* -X826Y511D01* -X847Y511D02* -X854Y511D01* -X881Y511D02* -X889Y511D01* -X927Y511D02* -X935Y511D01* -X981Y511D02* -X1007Y511D01* -X2595Y511D02* -X2602Y511D01* -X1Y510D02* -X8Y510D01* -X216Y510D02* -X224Y510D01* -X349Y510D02* -X359Y510D01* -X422Y510D02* -X430Y510D01* -X471Y510D02* -X480Y510D01* -X498Y510D02* -X507Y510D01* -X531Y510D02* -X539Y510D01* -X566Y510D02* -X574Y510D01* -X657Y510D02* -X680Y510D01* -X682Y510D02* -X697Y510D01* -X727Y510D02* -X756Y510D01* -X790Y510D02* -X815Y510D01* -X818Y510D02* -X826Y510D01* -X846Y510D02* -X854Y510D01* -X881Y510D02* -X889Y510D01* -X927Y510D02* -X935Y510D01* -X979Y510D02* -X1008Y510D01* -X2595Y510D02* -X2602Y510D01* -X1Y509D02* -X8Y509D01* -X216Y509D02* -X224Y509D01* -X350Y509D02* -X360Y509D01* -X422Y509D02* -X430Y509D01* -X471Y509D02* -X480Y509D01* -X499Y509D02* -X508Y509D01* -X531Y509D02* -X539Y509D01* -X566Y509D02* -X574Y509D01* -X656Y509D02* -X697Y509D01* -X726Y509D02* -X757Y509D01* -X789Y509D02* -X816Y509D01* -X818Y509D02* -X826Y509D01* -X846Y509D02* -X854Y509D01* -X881Y509D02* -X889Y509D01* -X927Y509D02* -X935Y509D01* -X978Y509D02* -X1009Y509D01* -X2595Y509D02* -X2602Y509D01* -X1Y508D02* -X8Y508D01* -X216Y508D02* -X224Y508D01* -X350Y508D02* -X361Y508D01* -X422Y508D02* -X430Y508D01* -X470Y508D02* -X479Y508D01* -X499Y508D02* -X508Y508D01* -X531Y508D02* -X539Y508D01* -X566Y508D02* -X574Y508D01* -X656Y508D02* -X698Y508D01* -X725Y508D02* -X758Y508D01* -X788Y508D02* -X826Y508D01* -X846Y508D02* -X854Y508D01* -X881Y508D02* -X889Y508D01* -X927Y508D02* -X935Y508D01* -X977Y508D02* -X1010Y508D01* -X2595Y508D02* -X2602Y508D01* -X1Y507D02* -X8Y507D01* -X216Y507D02* -X224Y507D01* -X351Y507D02* -X361Y507D01* -X422Y507D02* -X430Y507D01* -X470Y507D02* -X479Y507D01* -X500Y507D02* -X509Y507D01* -X531Y507D02* -X539Y507D01* -X566Y507D02* -X574Y507D01* -X656Y507D02* -X698Y507D01* -X724Y507D02* -X759Y507D01* -X787Y507D02* -X826Y507D01* -X846Y507D02* -X854Y507D01* -X881Y507D02* -X889Y507D01* -X927Y507D02* -X935Y507D01* -X976Y507D02* -X1011Y507D01* -X2595Y507D02* -X2602Y507D01* -X1Y506D02* -X8Y506D01* -X216Y506D02* -X224Y506D01* -X352Y506D02* -X362Y506D01* -X422Y506D02* -X430Y506D01* -X470Y506D02* -X478Y506D01* -X500Y506D02* -X509Y506D01* -X531Y506D02* -X539Y506D01* -X566Y506D02* -X574Y506D01* -X656Y506D02* -X699Y506D01* -X723Y506D02* -X760Y506D01* -X786Y506D02* -X826Y506D01* -X846Y506D02* -X854Y506D01* -X881Y506D02* -X889Y506D01* -X927Y506D02* -X935Y506D01* -X975Y506D02* -X1012Y506D01* -X2595Y506D02* -X2602Y506D01* -X1Y505D02* -X8Y505D01* -X216Y505D02* -X224Y505D01* -X353Y505D02* -X363Y505D01* -X422Y505D02* -X430Y505D01* -X469Y505D02* -X478Y505D01* -X501Y505D02* -X509Y505D01* -X531Y505D02* -X539Y505D01* -X566Y505D02* -X574Y505D01* -X656Y505D02* -X671Y505D01* -X673Y505D02* -X699Y505D01* -X722Y505D02* -X736Y505D01* -X747Y505D02* -X761Y505D01* -X785Y505D02* -X799Y505D01* -X806Y505D02* -X826Y505D01* -X847Y505D02* -X854Y505D01* -X881Y505D02* -X889Y505D01* -X927Y505D02* -X935Y505D01* -X975Y505D02* -X988Y505D01* -X1000Y505D02* -X1013Y505D01* -X2595Y505D02* -X2602Y505D01* -X1Y504D02* -X8Y504D01* -X216Y504D02* -X224Y504D01* -X353Y504D02* -X364Y504D01* -X422Y504D02* -X430Y504D01* -X469Y504D02* -X477Y504D01* -X501Y504D02* -X510Y504D01* -X531Y504D02* -X539Y504D01* -X566Y504D02* -X574Y504D01* -X656Y504D02* -X670Y504D01* -X674Y504D02* -X687Y504D01* -X691Y504D02* -X699Y504D01* -X722Y504D02* -X733Y504D01* -X750Y504D02* -X761Y504D01* -X785Y504D02* -X796Y504D01* -X809Y504D02* -X826Y504D01* -X847Y504D02* -X854Y504D01* -X881Y504D02* -X889Y504D01* -X927Y504D02* -X935Y504D01* -X974Y504D02* -X985Y504D01* -X1003Y504D02* -X1014Y504D01* -X2595Y504D02* -X2602Y504D01* -X1Y503D02* -X8Y503D01* -X216Y503D02* -X224Y503D01* -X354Y503D02* -X365Y503D01* -X422Y503D02* -X430Y503D01* -X469Y503D02* -X477Y503D01* -X502Y503D02* -X510Y503D01* -X531Y503D02* -X539Y503D01* -X566Y503D02* -X574Y503D01* -X656Y503D02* -X669Y503D01* -X675Y503D02* -X686Y503D01* -X691Y503D02* -X699Y503D01* -X721Y503D02* -X732Y503D01* -X752Y503D02* -X762Y503D01* -X784Y503D02* -X795Y503D01* -X810Y503D02* -X826Y503D01* -X847Y503D02* -X854Y503D01* -X881Y503D02* -X889Y503D01* -X927Y503D02* -X935Y503D01* -X974Y503D02* -X984Y503D01* -X1004Y503D02* -X1014Y503D01* -X2595Y503D02* -X2602Y503D01* -X1Y502D02* -X8Y502D01* -X216Y502D02* -X239Y502D01* -X281Y502D02* -X319Y502D01* -X355Y502D02* -X365Y502D01* -X422Y502D02* -X430Y502D01* -X468Y502D02* -X477Y502D01* -X502Y502D02* -X510Y502D01* -X531Y502D02* -X539Y502D01* -X566Y502D02* -X574Y502D01* -X656Y502D02* -X667Y502D01* -X675Y502D02* -X685Y502D01* -X691Y502D02* -X699Y502D01* -X721Y502D02* -X730Y502D01* -X753Y502D02* -X762Y502D01* -X784Y502D02* -X793Y502D01* -X811Y502D02* -X826Y502D01* -X847Y502D02* -X854Y502D01* -X881Y502D02* -X889Y502D01* -X927Y502D02* -X935Y502D01* -X973Y502D02* -X983Y502D01* -X1005Y502D02* -X1014Y502D01* -X2595Y502D02* -X2602Y502D01* -X1Y501D02* -X8Y501D01* -X216Y501D02* -X240Y501D01* -X280Y501D02* -X320Y501D01* -X356Y501D02* -X366Y501D01* -X422Y501D02* -X430Y501D01* -X468Y501D02* -X476Y501D01* -X502Y501D02* -X510Y501D01* -X531Y501D02* -X539Y501D01* -X565Y501D02* -X573Y501D01* -X656Y501D02* -X666Y501D01* -X675Y501D02* -X684Y501D01* -X691Y501D02* -X699Y501D01* -X721Y501D02* -X729Y501D01* -X754Y501D02* -X763Y501D01* -X784Y501D02* -X793Y501D01* -X812Y501D02* -X826Y501D01* -X847Y501D02* -X854Y501D01* -X881Y501D02* -X889Y501D01* -X927Y501D02* -X935Y501D01* -X973Y501D02* -X982Y501D01* -X1006Y501D02* -X1015Y501D01* -X2595Y501D02* -X2602Y501D01* -X1Y500D02* -X8Y500D01* -X216Y500D02* -X241Y500D01* -X279Y500D02* -X321Y500D01* -X357Y500D02* -X367Y500D01* -X422Y500D02* -X430Y500D01* -X468Y500D02* -X476Y500D01* -X503Y500D02* -X511Y500D01* -X531Y500D02* -X539Y500D01* -X564Y500D02* -X573Y500D01* -X656Y500D02* -X665Y500D01* -X675Y500D02* -X683Y500D01* -X691Y500D02* -X699Y500D01* -X720Y500D02* -X729Y500D01* -X754Y500D02* -X763Y500D01* -X783Y500D02* -X792Y500D01* -X814Y500D02* -X826Y500D01* -X847Y500D02* -X854Y500D01* -X881Y500D02* -X889Y500D01* -X927Y500D02* -X935Y500D01* -X973Y500D02* -X981Y500D01* -X1007Y500D02* -X1015Y500D01* -X2595Y500D02* -X2602Y500D01* -X1Y499D02* -X8Y499D01* -X216Y499D02* -X241Y499D01* -X279Y499D02* -X321Y499D01* -X357Y499D02* -X368Y499D01* -X422Y499D02* -X430Y499D01* -X468Y499D02* -X476Y499D01* -X503Y499D02* -X511Y499D01* -X531Y499D02* -X539Y499D01* -X561Y499D02* -X573Y499D01* -X656Y499D02* -X664Y499D01* -X675Y499D02* -X682Y499D01* -X692Y499D02* -X699Y499D01* -X720Y499D02* -X728Y499D01* -X755Y499D02* -X763Y499D01* -X783Y499D02* -X791Y499D01* -X815Y499D02* -X826Y499D01* -X847Y499D02* -X855Y499D01* -X881Y499D02* -X889Y499D01* -X927Y499D02* -X935Y499D01* -X973Y499D02* -X981Y499D01* -X1007Y499D02* -X1015Y499D01* -X2595Y499D02* -X2602Y499D01* -X1Y498D02* -X8Y498D01* -X216Y498D02* -X241Y498D01* -X279Y498D02* -X321Y498D01* -X358Y498D02* -X368Y498D01* -X422Y498D02* -X430Y498D01* -X468Y498D02* -X476Y498D01* -X503Y498D02* -X511Y498D01* -X531Y498D02* -X572Y498D01* -X656Y498D02* -X664Y498D01* -X675Y498D02* -X682Y498D01* -X692Y498D02* -X699Y498D01* -X720Y498D02* -X728Y498D01* -X755Y498D02* -X763Y498D01* -X783Y498D02* -X791Y498D01* -X816Y498D02* -X826Y498D01* -X847Y498D02* -X855Y498D01* -X881Y498D02* -X889Y498D01* -X927Y498D02* -X935Y498D01* -X973Y498D02* -X980Y498D01* -X1007Y498D02* -X1015Y498D01* -X2595Y498D02* -X2602Y498D01* -X1Y497D02* -X8Y497D01* -X216Y497D02* -X241Y497D01* -X279Y497D02* -X321Y497D01* -X359Y497D02* -X369Y497D01* -X422Y497D02* -X430Y497D01* -X468Y497D02* -X476Y497D01* -X503Y497D02* -X511Y497D01* -X531Y497D02* -X572Y497D01* -X656Y497D02* -X664Y497D01* -X675Y497D02* -X682Y497D01* -X692Y497D02* -X699Y497D01* -X720Y497D02* -X728Y497D01* -X755Y497D02* -X763Y497D01* -X783Y497D02* -X791Y497D01* -X817Y497D02* -X826Y497D01* -X847Y497D02* -X855Y497D01* -X881Y497D02* -X889Y497D01* -X927Y497D02* -X935Y497D01* -X973Y497D02* -X980Y497D01* -X1007Y497D02* -X1015Y497D01* -X2595Y497D02* -X2602Y497D01* -X1Y496D02* -X8Y496D01* -X216Y496D02* -X240Y496D01* -X279Y496D02* -X321Y496D01* -X360Y496D02* -X370Y496D01* -X422Y496D02* -X430Y496D01* -X468Y496D02* -X476Y496D01* -X502Y496D02* -X510Y496D01* -X531Y496D02* -X571Y496D01* -X656Y496D02* -X664Y496D01* -X675Y496D02* -X682Y496D01* -X692Y496D02* -X699Y496D01* -X720Y496D02* -X728Y496D01* -X755Y496D02* -X763Y496D01* -X783Y496D02* -X791Y496D01* -X818Y496D02* -X826Y496D01* -X847Y496D02* -X855Y496D01* -X881Y496D02* -X889Y496D01* -X927Y496D02* -X935Y496D01* -X973Y496D02* -X980Y496D01* -X1007Y496D02* -X1015Y496D01* -X2595Y496D02* -X2602Y496D01* -X1Y495D02* -X8Y495D01* -X216Y495D02* -X239Y495D01* -X279Y495D02* -X321Y495D01* -X360Y495D02* -X371Y495D01* -X422Y495D02* -X430Y495D01* -X468Y495D02* -X476Y495D01* -X502Y495D02* -X510Y495D01* -X531Y495D02* -X571Y495D01* -X656Y495D02* -X664Y495D01* -X675Y495D02* -X682Y495D01* -X692Y495D02* -X699Y495D01* -X720Y495D02* -X728Y495D01* -X755Y495D02* -X763Y495D01* -X783Y495D02* -X791Y495D01* -X818Y495D02* -X826Y495D01* -X847Y495D02* -X855Y495D01* -X881Y495D02* -X889Y495D01* -X927Y495D02* -X935Y495D01* -X973Y495D02* -X980Y495D01* -X1007Y495D02* -X1015Y495D01* -X2595Y495D02* -X2602Y495D01* -X1Y494D02* -X8Y494D01* -X216Y494D02* -X237Y494D01* -X279Y494D02* -X321Y494D01* -X361Y494D02* -X372Y494D01* -X422Y494D02* -X430Y494D01* -X468Y494D02* -X477Y494D01* -X502Y494D02* -X510Y494D01* -X531Y494D02* -X570Y494D01* -X656Y494D02* -X664Y494D01* -X675Y494D02* -X682Y494D01* -X692Y494D02* -X699Y494D01* -X720Y494D02* -X728Y494D01* -X755Y494D02* -X763Y494D01* -X783Y494D02* -X791Y494D01* -X818Y494D02* -X826Y494D01* -X847Y494D02* -X855Y494D01* -X881Y494D02* -X889Y494D01* -X927Y494D02* -X935Y494D01* -X973Y494D02* -X980Y494D01* -X1007Y494D02* -X1015Y494D01* -X2595Y494D02* -X2602Y494D01* -X1Y493D02* -X8Y493D01* -X216Y493D02* -X224Y493D01* -X279Y493D02* -X321Y493D01* -X362Y493D02* -X372Y493D01* -X422Y493D02* -X430Y493D01* -X469Y493D02* -X477Y493D01* -X501Y493D02* -X510Y493D01* -X531Y493D02* -X568Y493D01* -X656Y493D02* -X664Y493D01* -X675Y493D02* -X682Y493D01* -X692Y493D02* -X700Y493D01* -X720Y493D02* -X728Y493D01* -X755Y493D02* -X763Y493D01* -X783Y493D02* -X791Y493D01* -X818Y493D02* -X826Y493D01* -X847Y493D02* -X855Y493D01* -X881Y493D02* -X889Y493D01* -X927Y493D02* -X935Y493D01* -X973Y493D02* -X980Y493D01* -X1007Y493D02* -X1015Y493D01* -X2595Y493D02* -X2602Y493D01* -X1Y492D02* -X8Y492D01* -X216Y492D02* -X224Y492D01* -X280Y492D02* -X320Y492D01* -X363Y492D02* -X373Y492D01* -X422Y492D02* -X430Y492D01* -X469Y492D02* -X478Y492D01* -X501Y492D02* -X510Y492D01* -X531Y492D02* -X567Y492D01* -X656Y492D02* -X664Y492D01* -X675Y492D02* -X682Y492D01* -X692Y492D02* -X700Y492D01* -X720Y492D02* -X728Y492D01* -X755Y492D02* -X763Y492D01* -X783Y492D02* -X791Y492D01* -X818Y492D02* -X826Y492D01* -X847Y492D02* -X855Y492D01* -X881Y492D02* -X889Y492D01* -X927Y492D02* -X935Y492D01* -X973Y492D02* -X980Y492D01* -X1007Y492D02* -X1015Y492D01* -X2595Y492D02* -X2602Y492D01* -X1Y491D02* -X8Y491D01* -X216Y491D02* -X224Y491D01* -X281Y491D02* -X319Y491D01* -X364Y491D02* -X374Y491D01* -X422Y491D02* -X430Y491D01* -X469Y491D02* -X478Y491D01* -X500Y491D02* -X509Y491D01* -X531Y491D02* -X565Y491D01* -X656Y491D02* -X664Y491D01* -X675Y491D02* -X682Y491D01* -X692Y491D02* -X700Y491D01* -X720Y491D02* -X728Y491D01* -X755Y491D02* -X763Y491D01* -X783Y491D02* -X791Y491D01* -X818Y491D02* -X826Y491D01* -X847Y491D02* -X855Y491D01* -X881Y491D02* -X889Y491D01* -X927Y491D02* -X935Y491D01* -X973Y491D02* -X1015Y491D01* -X2595Y491D02* -X2602Y491D01* -X1Y490D02* -X8Y490D01* -X216Y490D02* -X224Y490D01* -X364Y490D02* -X375Y490D01* -X422Y490D02* -X430Y490D01* -X470Y490D02* -X479Y490D01* -X500Y490D02* -X509Y490D01* -X531Y490D02* -X539Y490D01* -X656Y490D02* -X664Y490D01* -X675Y490D02* -X682Y490D01* -X692Y490D02* -X700Y490D01* -X720Y490D02* -X728Y490D01* -X755Y490D02* -X763Y490D01* -X783Y490D02* -X791Y490D01* -X818Y490D02* -X826Y490D01* -X847Y490D02* -X855Y490D01* -X881Y490D02* -X889Y490D01* -X927Y490D02* -X935Y490D01* -X973Y490D02* -X1015Y490D01* -X2595Y490D02* -X2602Y490D01* -X1Y489D02* -X8Y489D01* -X216Y489D02* -X224Y489D01* -X365Y489D02* -X375Y489D01* -X422Y489D02* -X430Y489D01* -X470Y489D02* -X479Y489D01* -X499Y489D02* -X508Y489D01* -X531Y489D02* -X539Y489D01* -X656Y489D02* -X664Y489D01* -X675Y489D02* -X682Y489D01* -X692Y489D02* -X700Y489D01* -X720Y489D02* -X728Y489D01* -X755Y489D02* -X763Y489D01* -X783Y489D02* -X791Y489D01* -X818Y489D02* -X826Y489D01* -X847Y489D02* -X855Y489D01* -X881Y489D02* -X889Y489D01* -X927Y489D02* -X935Y489D01* -X973Y489D02* -X1015Y489D01* -X2595Y489D02* -X2602Y489D01* -X1Y488D02* -X8Y488D01* -X216Y488D02* -X224Y488D01* -X366Y488D02* -X376Y488D01* -X422Y488D02* -X430Y488D01* -X471Y488D02* -X480Y488D01* -X499Y488D02* -X508Y488D01* -X531Y488D02* -X539Y488D01* -X656Y488D02* -X664Y488D01* -X675Y488D02* -X682Y488D01* -X692Y488D02* -X700Y488D01* -X720Y488D02* -X728Y488D01* -X755Y488D02* -X763Y488D01* -X783Y488D02* -X791Y488D01* -X818Y488D02* -X826Y488D01* -X847Y488D02* -X855Y488D01* -X881Y488D02* -X889Y488D01* -X927Y488D02* -X935Y488D01* -X973Y488D02* -X1015Y488D01* -X2595Y488D02* -X2602Y488D01* -X1Y487D02* -X8Y487D01* -X216Y487D02* -X224Y487D01* -X367Y487D02* -X377Y487D01* -X422Y487D02* -X430Y487D01* -X471Y487D02* -X480Y487D01* -X498Y487D02* -X507Y487D01* -X531Y487D02* -X539Y487D01* -X656Y487D02* -X664Y487D01* -X675Y487D02* -X682Y487D01* -X692Y487D02* -X700Y487D01* -X720Y487D02* -X728Y487D01* -X755Y487D02* -X763Y487D01* -X783Y487D02* -X791Y487D01* -X818Y487D02* -X826Y487D01* -X847Y487D02* -X855Y487D01* -X881Y487D02* -X889Y487D01* -X927Y487D02* -X935Y487D01* -X973Y487D02* -X1015Y487D01* -X2595Y487D02* -X2602Y487D01* -X1Y486D02* -X8Y486D01* -X216Y486D02* -X224Y486D01* -X367Y486D02* -X378Y486D01* -X422Y486D02* -X430Y486D01* -X472Y486D02* -X481Y486D01* -X498Y486D02* -X507Y486D01* -X531Y486D02* -X539Y486D01* -X656Y486D02* -X664Y486D01* -X675Y486D02* -X682Y486D01* -X692Y486D02* -X700Y486D01* -X720Y486D02* -X728Y486D01* -X755Y486D02* -X763Y486D01* -X783Y486D02* -X791Y486D01* -X818Y486D02* -X826Y486D01* -X847Y486D02* -X855Y486D01* -X881Y486D02* -X889Y486D01* -X927Y486D02* -X935Y486D01* -X973Y486D02* -X1015Y486D01* -X2595Y486D02* -X2602Y486D01* -X1Y485D02* -X8Y485D01* -X216Y485D02* -X224Y485D01* -X368Y485D02* -X379Y485D01* -X422Y485D02* -X430Y485D01* -X472Y485D02* -X481Y485D01* -X497Y485D02* -X506Y485D01* -X531Y485D02* -X539Y485D01* -X656Y485D02* -X664Y485D01* -X675Y485D02* -X682Y485D01* -X692Y485D02* -X700Y485D01* -X720Y485D02* -X728Y485D01* -X755Y485D02* -X763Y485D01* -X783Y485D02* -X791Y485D01* -X818Y485D02* -X826Y485D01* -X847Y485D02* -X855Y485D01* -X881Y485D02* -X889Y485D01* -X927Y485D02* -X935Y485D01* -X973Y485D02* -X1015Y485D01* -X2595Y485D02* -X2602Y485D01* -X1Y484D02* -X8Y484D01* -X216Y484D02* -X224Y484D01* -X369Y484D02* -X379Y484D01* -X422Y484D02* -X430Y484D01* -X473Y484D02* -X482Y484D01* -X497Y484D02* -X506Y484D01* -X531Y484D02* -X539Y484D01* -X656Y484D02* -X664Y484D01* -X675Y484D02* -X682Y484D01* -X692Y484D02* -X700Y484D01* -X720Y484D02* -X728Y484D01* -X755Y484D02* -X763Y484D01* -X783Y484D02* -X791Y484D01* -X818Y484D02* -X826Y484D01* -X847Y484D02* -X855Y484D01* -X881Y484D02* -X889Y484D01* -X927Y484D02* -X935Y484D01* -X973Y484D02* -X1014Y484D01* -X2595Y484D02* -X2602Y484D01* -X1Y483D02* -X8Y483D01* -X216Y483D02* -X224Y483D01* -X370Y483D02* -X380Y483D01* -X422Y483D02* -X430Y483D01* -X473Y483D02* -X482Y483D01* -X496Y483D02* -X505Y483D01* -X531Y483D02* -X539Y483D01* -X656Y483D02* -X664Y483D01* -X675Y483D02* -X682Y483D01* -X692Y483D02* -X700Y483D01* -X720Y483D02* -X728Y483D01* -X755Y483D02* -X763Y483D01* -X783Y483D02* -X791Y483D01* -X818Y483D02* -X826Y483D01* -X847Y483D02* -X855Y483D01* -X881Y483D02* -X889Y483D01* -X927Y483D02* -X935Y483D01* -X973Y483D02* -X1012Y483D01* -X2595Y483D02* -X2602Y483D01* -X1Y482D02* -X8Y482D01* -X216Y482D02* -X224Y482D01* -X371Y482D02* -X381Y482D01* -X422Y482D02* -X430Y482D01* -X474Y482D02* -X483Y482D01* -X496Y482D02* -X505Y482D01* -X531Y482D02* -X539Y482D01* -X656Y482D02* -X664Y482D01* -X675Y482D02* -X682Y482D01* -X692Y482D02* -X700Y482D01* -X720Y482D02* -X728Y482D01* -X755Y482D02* -X763Y482D01* -X783Y482D02* -X791Y482D01* -X818Y482D02* -X826Y482D01* -X847Y482D02* -X855Y482D01* -X881Y482D02* -X889Y482D01* -X927Y482D02* -X935Y482D01* -X973Y482D02* -X980Y482D01* -X2595Y482D02* -X2602Y482D01* -X1Y481D02* -X8Y481D01* -X216Y481D02* -X224Y481D01* -X371Y481D02* -X382Y481D01* -X422Y481D02* -X430Y481D01* -X474Y481D02* -X483Y481D01* -X495Y481D02* -X504Y481D01* -X531Y481D02* -X539Y481D01* -X656Y481D02* -X664Y481D01* -X675Y481D02* -X682Y481D01* -X692Y481D02* -X700Y481D01* -X720Y481D02* -X728Y481D01* -X755Y481D02* -X763Y481D01* -X783Y481D02* -X791Y481D01* -X817Y481D02* -X826Y481D01* -X847Y481D02* -X855Y481D01* -X879Y481D02* -X889Y481D01* -X927Y481D02* -X935Y481D01* -X973Y481D02* -X980Y481D01* -X2595Y481D02* -X2602Y481D01* -X1Y480D02* -X8Y480D01* -X216Y480D02* -X224Y480D01* -X345Y480D02* -X347Y480D01* -X372Y480D02* -X382Y480D01* -X422Y480D02* -X430Y480D01* -X475Y480D02* -X484Y480D01* -X495Y480D02* -X504Y480D01* -X531Y480D02* -X539Y480D01* -X656Y480D02* -X664Y480D01* -X675Y480D02* -X682Y480D01* -X692Y480D02* -X700Y480D01* -X720Y480D02* -X728Y480D01* -X755Y480D02* -X763Y480D01* -X783Y480D02* -X791Y480D01* -X816Y480D02* -X826Y480D01* -X847Y480D02* -X855Y480D01* -X878Y480D02* -X889Y480D01* -X927Y480D02* -X935Y480D01* -X973Y480D02* -X980Y480D01* -X2595Y480D02* -X2602Y480D01* -X1Y479D02* -X8Y479D01* -X216Y479D02* -X224Y479D01* -X343Y479D02* -X348Y479D01* -X373Y479D02* -X383Y479D01* -X422Y479D02* -X430Y479D01* -X475Y479D02* -X484Y479D01* -X494Y479D02* -X503Y479D01* -X531Y479D02* -X539Y479D01* -X656Y479D02* -X664Y479D01* -X675Y479D02* -X682Y479D01* -X692Y479D02* -X700Y479D01* -X720Y479D02* -X728Y479D01* -X755Y479D02* -X763Y479D01* -X783Y479D02* -X791Y479D01* -X815Y479D02* -X826Y479D01* -X847Y479D02* -X855Y479D01* -X876Y479D02* -X889Y479D01* -X927Y479D02* -X935Y479D01* -X973Y479D02* -X981Y479D01* -X2595Y479D02* -X2602Y479D01* -X1Y478D02* -X8Y478D01* -X216Y478D02* -X224Y478D01* -X342Y478D02* -X349Y478D01* -X374Y478D02* -X384Y478D01* -X422Y478D02* -X430Y478D01* -X476Y478D02* -X485Y478D01* -X494Y478D02* -X503Y478D01* -X531Y478D02* -X539Y478D01* -X656Y478D02* -X664Y478D01* -X675Y478D02* -X682Y478D01* -X692Y478D02* -X700Y478D01* -X720Y478D02* -X729Y478D01* -X754Y478D02* -X763Y478D01* -X784Y478D02* -X792Y478D01* -X814Y478D02* -X826Y478D01* -X847Y478D02* -X855Y478D01* -X875Y478D02* -X889Y478D01* -X927Y478D02* -X935Y478D01* -X973Y478D02* -X981Y478D01* -X2595Y478D02* -X2602Y478D01* -X1Y477D02* -X8Y477D01* -X216Y477D02* -X224Y477D01* -X342Y477D02* -X350Y477D01* -X374Y477D02* -X384Y477D01* -X422Y477D02* -X430Y477D01* -X476Y477D02* -X485Y477D01* -X493Y477D02* -X502Y477D01* -X531Y477D02* -X539Y477D01* -X656Y477D02* -X664Y477D01* -X675Y477D02* -X682Y477D01* -X692Y477D02* -X700Y477D01* -X721Y477D02* -X729Y477D01* -X754Y477D02* -X763Y477D01* -X784Y477D02* -X792Y477D01* -X812Y477D02* -X826Y477D01* -X847Y477D02* -X855Y477D01* -X873Y477D02* -X889Y477D01* -X927Y477D02* -X935Y477D01* -X973Y477D02* -X982Y477D01* -X2595Y477D02* -X2602Y477D01* -X1Y476D02* -X8Y476D01* -X216Y476D02* -X224Y476D01* -X342Y476D02* -X350Y476D01* -X375Y476D02* -X384Y476D01* -X422Y476D02* -X430Y476D01* -X477Y476D02* -X486Y476D01* -X493Y476D02* -X502Y476D01* -X531Y476D02* -X539Y476D01* -X656Y476D02* -X664Y476D01* -X675Y476D02* -X682Y476D01* -X692Y476D02* -X700Y476D01* -X721Y476D02* -X730Y476D01* -X753Y476D02* -X762Y476D01* -X784Y476D02* -X793Y476D01* -X811Y476D02* -X826Y476D01* -X848Y476D02* -X856Y476D01* -X872Y476D02* -X889Y476D01* -X927Y476D02* -X935Y476D01* -X973Y476D02* -X983Y476D01* -X2595Y476D02* -X2602Y476D01* -X1Y475D02* -X8Y475D01* -X216Y475D02* -X224Y475D01* -X342Y475D02* -X350Y475D01* -X376Y475D02* -X384Y475D01* -X422Y475D02* -X430Y475D01* -X477Y475D02* -X486Y475D01* -X492Y475D02* -X501Y475D01* -X531Y475D02* -X539Y475D01* -X656Y475D02* -X664Y475D01* -X675Y475D02* -X682Y475D01* -X692Y475D02* -X700Y475D01* -X721Y475D02* -X731Y475D01* -X752Y475D02* -X762Y475D01* -X784Y475D02* -X795Y475D01* -X810Y475D02* -X826Y475D01* -X848Y475D02* -X856Y475D01* -X870Y475D02* -X889Y475D01* -X927Y475D02* -X935Y475D01* -X973Y475D02* -X984Y475D01* -X2595Y475D02* -X2602Y475D01* -X1Y474D02* -X8Y474D01* -X216Y474D02* -X224Y474D01* -X342Y474D02* -X351Y474D01* -X377Y474D02* -X384Y474D01* -X422Y474D02* -X430Y474D01* -X478Y474D02* -X487Y474D01* -X492Y474D02* -X501Y474D01* -X531Y474D02* -X539Y474D01* -X656Y474D02* -X664Y474D01* -X675Y474D02* -X682Y474D01* -X692Y474D02* -X700Y474D01* -X722Y474D02* -X733Y474D01* -X750Y474D02* -X761Y474D01* -X785Y474D02* -X796Y474D01* -X809Y474D02* -X826Y474D01* -X848Y474D02* -X857Y474D01* -X868Y474D02* -X889Y474D01* -X927Y474D02* -X935Y474D01* -X974Y474D02* -X985Y474D01* -X2595Y474D02* -X2602Y474D01* -X1Y473D02* -X8Y473D01* -X216Y473D02* -X224Y473D01* -X342Y473D02* -X353Y473D01* -X376Y473D02* -X384Y473D01* -X422Y473D02* -X430Y473D01* -X478Y473D02* -X500Y473D01* -X531Y473D02* -X539Y473D01* -X656Y473D02* -X664Y473D01* -X675Y473D02* -X682Y473D01* -X692Y473D02* -X700Y473D01* -X722Y473D02* -X735Y473D01* -X748Y473D02* -X761Y473D01* -X785Y473D02* -X798Y473D01* -X806Y473D02* -X826Y473D01* -X848Y473D02* -X859Y473D01* -X867Y473D02* -X889Y473D01* -X926Y473D02* -X935Y473D01* -X974Y473D02* -X988Y473D01* -X2595Y473D02* -X2602Y473D01* -X1Y472D02* -X8Y472D01* -X216Y472D02* -X257Y472D01* -X343Y472D02* -X384Y472D01* -X422Y472D02* -X430Y472D01* -X479Y472D02* -X500Y472D01* -X531Y472D02* -X539Y472D01* -X656Y472D02* -X664Y472D01* -X675Y472D02* -X682Y472D01* -X692Y472D02* -X700Y472D01* -X723Y472D02* -X760Y472D01* -X786Y472D02* -X826Y472D01* -X849Y472D02* -X889Y472D01* -X916Y472D02* -X946Y472D01* -X975Y472D02* -X1013Y472D01* -X2595Y472D02* -X2602Y472D01* -X1Y471D02* -X8Y471D01* -X216Y471D02* -X257Y471D01* -X343Y471D02* -X384Y471D01* -X422Y471D02* -X430Y471D01* -X479Y471D02* -X499Y471D01* -X531Y471D02* -X539Y471D01* -X656Y471D02* -X664Y471D01* -X675Y471D02* -X682Y471D01* -X692Y471D02* -X700Y471D01* -X724Y471D02* -X759Y471D01* -X787Y471D02* -X826Y471D01* -X849Y471D02* -X879Y471D01* -X881Y471D02* -X889Y471D01* -X915Y471D02* -X947Y471D01* -X976Y471D02* -X1014Y471D01* -X2595Y471D02* -X2602Y471D01* -X1Y470D02* -X8Y470D01* -X216Y470D02* -X258Y470D01* -X344Y470D02* -X383Y470D01* -X422Y470D02* -X430Y470D01* -X480Y470D02* -X499Y470D01* -X531Y470D02* -X539Y470D01* -X656Y470D02* -X664Y470D01* -X675Y470D02* -X682Y470D01* -X693Y470D02* -X700Y470D01* -X725Y470D02* -X758Y470D01* -X788Y470D02* -X826Y470D01* -X850Y470D02* -X878Y470D01* -X881Y470D02* -X889Y470D01* -X914Y470D02* -X947Y470D01* -X977Y470D02* -X1015Y470D01* -X2595Y470D02* -X2602Y470D01* -X1Y469D02* -X8Y469D01* -X216Y469D02* -X258Y469D01* -X344Y469D02* -X383Y469D01* -X422Y469D02* -X430Y469D01* -X480Y469D02* -X498Y469D01* -X531Y469D02* -X539Y469D01* -X656Y469D02* -X664Y469D01* -X675Y469D02* -X682Y469D01* -X693Y469D02* -X700Y469D01* -X726Y469D02* -X757Y469D01* -X789Y469D02* -X816Y469D01* -X818Y469D02* -X826Y469D01* -X850Y469D02* -X876Y469D01* -X881Y469D02* -X889Y469D01* -X914Y469D02* -X948Y469D01* -X978Y469D02* -X1015Y469D01* -X2595Y469D02* -X2602Y469D01* -X1Y468D02* -X8Y468D01* -X216Y468D02* -X258Y468D01* -X345Y468D02* -X382Y468D01* -X422Y468D02* -X430Y468D01* -X481Y468D02* -X497Y468D01* -X531Y468D02* -X539Y468D01* -X657Y468D02* -X664Y468D01* -X675Y468D02* -X682Y468D01* -X693Y468D02* -X700Y468D01* -X727Y468D02* -X756Y468D01* -X790Y468D02* -X815Y468D01* -X818Y468D02* -X826Y468D01* -X851Y468D02* -X874Y468D01* -X881Y468D02* -X889Y468D01* -X914Y468D02* -X948Y468D01* -X979Y468D02* -X1015Y468D01* -X2595Y468D02* -X2602Y468D01* -X1Y467D02* -X8Y467D01* -X216Y467D02* -X258Y467D01* -X346Y467D02* -X381Y467D01* -X423Y467D02* -X430Y467D01* -X482Y467D02* -X496Y467D01* -X531Y467D02* -X539Y467D01* -X657Y467D02* -X664Y467D01* -X675Y467D02* -X682Y467D01* -X693Y467D02* -X700Y467D01* -X728Y467D02* -X755Y467D01* -X791Y467D02* -X814Y467D01* -X818Y467D02* -X826Y467D01* -X852Y467D02* -X873Y467D01* -X881Y467D02* -X889Y467D01* -X914Y467D02* -X947Y467D01* -X981Y467D02* -X1015Y467D01* -X2595Y467D02* -X2602Y467D01* -X1Y466D02* -X8Y466D01* -X216Y466D02* -X257Y466D01* -X347Y466D02* -X380Y466D01* -X423Y466D02* -X429Y466D01* -X484Y466D02* -X495Y466D01* -X532Y466D02* -X538Y466D01* -X657Y466D02* -X663Y466D01* -X675Y466D02* -X681Y466D01* -X694Y466D02* -X700Y466D01* -X730Y466D02* -X753Y466D01* -X793Y466D02* -X812Y466D01* -X819Y466D02* -X825Y466D01* -X854Y466D02* -X871Y466D01* -X882Y466D02* -X888Y466D01* -X915Y466D02* -X947Y466D01* -X982Y466D02* -X1014Y466D01* -X2595Y466D02* -X2602Y466D01* -X1Y465D02* -X8Y465D01* -X216Y465D02* -X256Y465D01* -X349Y465D02* -X379Y465D01* -X424Y465D02* -X428Y465D01* -X486Y465D02* -X493Y465D01* -X533Y465D02* -X537Y465D01* -X658Y465D02* -X662Y465D01* -X676Y465D02* -X680Y465D01* -X695Y465D02* -X699Y465D01* -X732Y465D02* -X751Y465D01* -X795Y465D02* -X810Y465D01* -X820Y465D02* -X824Y465D01* -X856Y465D02* -X869Y465D01* -X883Y465D02* -X887Y465D01* -X916Y465D02* -X946Y465D01* -X984Y465D02* -X1013Y465D01* -X2595Y465D02* -X2602Y465D01* -X1Y464D02* -X8Y464D01* -X2595Y464D02* -X2602Y464D01* -X1Y463D02* -X8Y463D01* -X2595Y463D02* -X2602Y463D01* -X1Y462D02* -X8Y462D01* -X2595Y462D02* -X2602Y462D01* -X1Y461D02* -X8Y461D01* -X2595Y461D02* -X2602Y461D01* -X1Y460D02* -X8Y460D01* -X2595Y460D02* -X2602Y460D01* -X1Y459D02* -X8Y459D01* -X2595Y459D02* -X2602Y459D01* -X1Y458D02* -X8Y458D01* -X2595Y458D02* -X2602Y458D01* -X1Y457D02* -X8Y457D01* -X2595Y457D02* -X2602Y457D01* -X1Y456D02* -X8Y456D01* -X2595Y456D02* -X2602Y456D01* -X1Y455D02* -X8Y455D01* -X2595Y455D02* -X2602Y455D01* -X1Y454D02* -X8Y454D01* -X2595Y454D02* -X2602Y454D01* -X1Y453D02* -X8Y453D01* -X2595Y453D02* -X2602Y453D01* -X1Y452D02* -X8Y452D01* -X2595Y452D02* -X2602Y452D01* -X1Y451D02* -X8Y451D01* -X2595Y451D02* -X2602Y451D01* -X1Y450D02* -X8Y450D01* -X2595Y450D02* -X2602Y450D01* -X1Y449D02* -X8Y449D01* -X2595Y449D02* -X2602Y449D01* -X1Y448D02* -X8Y448D01* -X2595Y448D02* -X2602Y448D01* -X1Y447D02* -X8Y447D01* -X2595Y447D02* -X2602Y447D01* -X1Y446D02* -X8Y446D01* -X2595Y446D02* -X2602Y446D01* -X1Y445D02* -X8Y445D01* -X2595Y445D02* -X2602Y445D01* -X1Y444D02* -X8Y444D01* -X2595Y444D02* -X2602Y444D01* -X1Y443D02* -X8Y443D01* -X2595Y443D02* -X2602Y443D01* -X1Y442D02* -X8Y442D01* -X2595Y442D02* -X2602Y442D01* -X1Y441D02* -X8Y441D01* -X2595Y441D02* -X2602Y441D01* -X1Y440D02* -X8Y440D01* -X2595Y440D02* -X2602Y440D01* -X1Y439D02* -X8Y439D01* -X2595Y439D02* -X2602Y439D01* -X1Y438D02* -X8Y438D01* -X2595Y438D02* -X2602Y438D01* -X1Y437D02* -X8Y437D01* -X2595Y437D02* -X2602Y437D01* -X1Y436D02* -X8Y436D01* -X2595Y436D02* -X2602Y436D01* -X1Y435D02* -X8Y435D01* -X2595Y435D02* -X2602Y435D01* -X1Y434D02* -X8Y434D01* -X2595Y434D02* -X2602Y434D01* -X1Y433D02* -X8Y433D01* -X2595Y433D02* -X2602Y433D01* -X1Y432D02* -X8Y432D01* -X2595Y432D02* -X2602Y432D01* -X1Y431D02* -X8Y431D01* -X2595Y431D02* -X2602Y431D01* -X1Y430D02* -X8Y430D01* -X2595Y430D02* -X2602Y430D01* -X1Y429D02* -X8Y429D01* -X2595Y429D02* -X2602Y429D01* -X1Y428D02* -X8Y428D01* -X2595Y428D02* -X2602Y428D01* -X1Y427D02* -X8Y427D01* -X2595Y427D02* -X2602Y427D01* -X1Y426D02* -X8Y426D01* -X2595Y426D02* -X2602Y426D01* -X1Y425D02* -X8Y425D01* -X2595Y425D02* -X2602Y425D01* -X1Y424D02* -X8Y424D01* -X2595Y424D02* -X2602Y424D01* -X1Y423D02* -X8Y423D01* -X2595Y423D02* -X2602Y423D01* -X1Y422D02* -X8Y422D01* -X2595Y422D02* -X2602Y422D01* -X1Y421D02* -X8Y421D01* -X2595Y421D02* -X2602Y421D01* -X1Y420D02* -X8Y420D01* -X2595Y420D02* -X2602Y420D01* -X1Y419D02* -X8Y419D01* -X2595Y419D02* -X2602Y419D01* -X1Y418D02* -X8Y418D01* -X2595Y418D02* -X2602Y418D01* -X1Y417D02* -X8Y417D01* -X2595Y417D02* -X2602Y417D01* -X1Y416D02* -X8Y416D01* -X2595Y416D02* -X2602Y416D01* -X1Y415D02* -X8Y415D01* -X2595Y415D02* -X2602Y415D01* -X1Y414D02* -X8Y414D01* -X2595Y414D02* -X2602Y414D01* -X1Y413D02* -X8Y413D01* -X2595Y413D02* -X2602Y413D01* -X1Y412D02* -X8Y412D01* -X2595Y412D02* -X2602Y412D01* -X1Y411D02* -X8Y411D01* -X2595Y411D02* -X2602Y411D01* -X1Y410D02* -X8Y410D01* -X2595Y410D02* -X2602Y410D01* -X1Y409D02* -X8Y409D01* -X2595Y409D02* -X2602Y409D01* -X1Y408D02* -X8Y408D01* -X2595Y408D02* -X2602Y408D01* -X1Y407D02* -X8Y407D01* -X2595Y407D02* -X2602Y407D01* -X1Y406D02* -X8Y406D01* -X2595Y406D02* -X2602Y406D01* -X1Y405D02* -X8Y405D01* -X2595Y405D02* -X2602Y405D01* -X1Y404D02* -X8Y404D01* -X2595Y404D02* -X2602Y404D01* -X1Y403D02* -X8Y403D01* -X2595Y403D02* -X2602Y403D01* -X1Y402D02* -X8Y402D01* -X2595Y402D02* -X2602Y402D01* -X1Y401D02* -X8Y401D01* -X2595Y401D02* -X2602Y401D01* -X1Y400D02* -X8Y400D01* -X2595Y400D02* -X2602Y400D01* -X1Y399D02* -X8Y399D01* -X2595Y399D02* -X2602Y399D01* -X1Y398D02* -X8Y398D01* -X2595Y398D02* -X2602Y398D01* -X1Y397D02* -X8Y397D01* -X2595Y397D02* -X2602Y397D01* -X1Y396D02* -X8Y396D01* -X2595Y396D02* -X2602Y396D01* -X1Y395D02* -X8Y395D01* -X2595Y395D02* -X2602Y395D01* -X1Y394D02* -X8Y394D01* -X2595Y394D02* -X2602Y394D01* -X1Y393D02* -X8Y393D01* -X2595Y393D02* -X2602Y393D01* -X1Y392D02* -X8Y392D01* -X2595Y392D02* -X2602Y392D01* -X1Y391D02* -X8Y391D01* -X2595Y391D02* -X2602Y391D01* -X1Y390D02* -X8Y390D01* -X2595Y390D02* -X2602Y390D01* -X1Y389D02* -X8Y389D01* -X2595Y389D02* -X2602Y389D01* -X1Y388D02* -X8Y388D01* -X2595Y388D02* -X2602Y388D01* -X1Y387D02* -X8Y387D01* -X2595Y387D02* -X2602Y387D01* -X1Y386D02* -X8Y386D01* -X2595Y386D02* -X2602Y386D01* -X1Y385D02* -X8Y385D01* -X2595Y385D02* -X2602Y385D01* -X1Y384D02* -X8Y384D01* -X2595Y384D02* -X2602Y384D01* -X1Y383D02* -X8Y383D01* -X2595Y383D02* -X2602Y383D01* -X1Y382D02* -X8Y382D01* -X2595Y382D02* -X2602Y382D01* -X1Y381D02* -X8Y381D01* -X2595Y381D02* -X2602Y381D01* -X1Y380D02* -X8Y380D01* -X2595Y380D02* -X2602Y380D01* -X1Y379D02* -X8Y379D01* -X2595Y379D02* -X2602Y379D01* -X1Y378D02* -X8Y378D01* -X2595Y378D02* -X2602Y378D01* -X1Y377D02* -X8Y377D01* -X2595Y377D02* -X2602Y377D01* -X1Y376D02* -X8Y376D01* -X2595Y376D02* -X2602Y376D01* -X1Y375D02* -X8Y375D01* -X2595Y375D02* -X2602Y375D01* -X1Y374D02* -X8Y374D01* -X2595Y374D02* -X2602Y374D01* -X1Y373D02* -X8Y373D01* -X2595Y373D02* -X2602Y373D01* -X1Y372D02* -X8Y372D01* -X2595Y372D02* -X2602Y372D01* -X1Y371D02* -X8Y371D01* -X2595Y371D02* -X2602Y371D01* -X1Y370D02* -X8Y370D01* -X2595Y370D02* -X2602Y370D01* -X1Y369D02* -X8Y369D01* -X2595Y369D02* -X2602Y369D01* -X1Y368D02* -X8Y368D01* -X2595Y368D02* -X2602Y368D01* -X1Y367D02* -X8Y367D01* -X2595Y367D02* -X2602Y367D01* -X1Y366D02* -X8Y366D01* -X2595Y366D02* -X2602Y366D01* -X1Y365D02* -X8Y365D01* -X2595Y365D02* -X2602Y365D01* -X1Y364D02* -X8Y364D01* -X2595Y364D02* -X2602Y364D01* -X1Y363D02* -X8Y363D01* -X2595Y363D02* -X2602Y363D01* -X1Y362D02* -X8Y362D01* -X2595Y362D02* -X2602Y362D01* -X1Y361D02* -X8Y361D01* -X2595Y361D02* -X2602Y361D01* -X1Y360D02* -X8Y360D01* -X2595Y360D02* -X2602Y360D01* -X1Y359D02* -X8Y359D01* -X2595Y359D02* -X2602Y359D01* -X1Y358D02* -X8Y358D01* -X2595Y358D02* -X2602Y358D01* -X1Y357D02* -X8Y357D01* -X2595Y357D02* -X2602Y357D01* -X1Y356D02* -X8Y356D01* -X2595Y356D02* -X2602Y356D01* -X1Y355D02* -X8Y355D01* -X2595Y355D02* -X2602Y355D01* -X1Y354D02* -X8Y354D01* -X2595Y354D02* -X2602Y354D01* -X1Y353D02* -X8Y353D01* -X2595Y353D02* -X2602Y353D01* -X1Y352D02* -X8Y352D01* -X2595Y352D02* -X2602Y352D01* -X1Y351D02* -X8Y351D01* -X2595Y351D02* -X2602Y351D01* -X1Y350D02* -X8Y350D01* -X2595Y350D02* -X2602Y350D01* -X1Y349D02* -X8Y349D01* -X2595Y349D02* -X2602Y349D01* -X1Y348D02* -X8Y348D01* -X2595Y348D02* -X2602Y348D01* -X1Y347D02* -X8Y347D01* -X2595Y347D02* -X2602Y347D01* -X1Y346D02* -X8Y346D01* -X2595Y346D02* -X2602Y346D01* -X1Y345D02* -X8Y345D01* -X2595Y345D02* -X2602Y345D01* -X1Y344D02* -X8Y344D01* -X2595Y344D02* -X2602Y344D01* -X1Y343D02* -X8Y343D01* -X2595Y343D02* -X2602Y343D01* -X1Y342D02* -X8Y342D01* -X2595Y342D02* -X2602Y342D01* -X1Y341D02* -X8Y341D01* -X2595Y341D02* -X2602Y341D01* -X1Y340D02* -X8Y340D01* -X2595Y340D02* -X2602Y340D01* -X1Y339D02* -X8Y339D01* -X2595Y339D02* -X2602Y339D01* -X1Y338D02* -X8Y338D01* -X2595Y338D02* -X2602Y338D01* -X1Y337D02* -X8Y337D01* -X2595Y337D02* -X2602Y337D01* -X1Y336D02* -X8Y336D01* -X2595Y336D02* -X2602Y336D01* -X1Y335D02* -X8Y335D01* -X2595Y335D02* -X2602Y335D01* -X1Y334D02* -X8Y334D01* -X2595Y334D02* -X2602Y334D01* -X1Y333D02* -X8Y333D01* -X2595Y333D02* -X2602Y333D01* -X1Y332D02* -X8Y332D01* -X2595Y332D02* -X2602Y332D01* -X1Y331D02* -X8Y331D01* -X2595Y331D02* -X2602Y331D01* -X1Y330D02* -X8Y330D01* -X2595Y330D02* -X2602Y330D01* -X1Y329D02* -X8Y329D01* -X2595Y329D02* -X2602Y329D01* -X1Y328D02* -X8Y328D01* -X2595Y328D02* -X2602Y328D01* -X1Y327D02* -X8Y327D01* -X2595Y327D02* -X2602Y327D01* -X1Y326D02* -X8Y326D01* -X2595Y326D02* -X2602Y326D01* -X1Y325D02* -X8Y325D01* -X2595Y325D02* -X2602Y325D01* -X1Y324D02* -X8Y324D01* -X2595Y324D02* -X2602Y324D01* -X1Y323D02* -X8Y323D01* -X2595Y323D02* -X2602Y323D01* -X1Y322D02* -X8Y322D01* -X2595Y322D02* -X2602Y322D01* -X1Y321D02* -X8Y321D01* -X2595Y321D02* -X2602Y321D01* -X1Y320D02* -X8Y320D01* -X2595Y320D02* -X2602Y320D01* -X1Y319D02* -X8Y319D01* -X2595Y319D02* -X2602Y319D01* -X1Y318D02* -X8Y318D01* -X2595Y318D02* -X2602Y318D01* -X1Y317D02* -X8Y317D01* -X2595Y317D02* -X2602Y317D01* -X1Y316D02* -X8Y316D01* -X2595Y316D02* -X2602Y316D01* -X1Y315D02* -X8Y315D01* -X2595Y315D02* -X2602Y315D01* -X1Y314D02* -X8Y314D01* -X2595Y314D02* -X2602Y314D01* -X1Y313D02* -X8Y313D01* -X2595Y313D02* -X2602Y313D01* -X1Y312D02* -X8Y312D01* -X2595Y312D02* -X2602Y312D01* -X1Y311D02* -X8Y311D01* -X2595Y311D02* -X2602Y311D01* -X1Y310D02* -X8Y310D01* -X2595Y310D02* -X2602Y310D01* -X1Y309D02* -X8Y309D01* -X2595Y309D02* -X2602Y309D01* -X1Y308D02* -X8Y308D01* -X2595Y308D02* -X2602Y308D01* -X1Y307D02* -X8Y307D01* -X2595Y307D02* -X2602Y307D01* -X1Y306D02* -X8Y306D01* -X2595Y306D02* -X2602Y306D01* -X1Y305D02* -X8Y305D01* -X2595Y305D02* -X2602Y305D01* -X1Y304D02* -X8Y304D01* -X2595Y304D02* -X2602Y304D01* -X1Y303D02* -X8Y303D01* -X2595Y303D02* -X2602Y303D01* -X1Y302D02* -X8Y302D01* -X2595Y302D02* -X2602Y302D01* -X1Y301D02* -X8Y301D01* -X2595Y301D02* -X2602Y301D01* -X1Y300D02* -X8Y300D01* -X2595Y300D02* -X2602Y300D01* -X1Y299D02* -X8Y299D01* -X2595Y299D02* -X2602Y299D01* -X1Y298D02* -X8Y298D01* -X2595Y298D02* -X2602Y298D01* -X1Y297D02* -X8Y297D01* -X2595Y297D02* -X2602Y297D01* -X1Y296D02* -X8Y296D01* -X2595Y296D02* -X2602Y296D01* -X1Y295D02* -X8Y295D01* -X2595Y295D02* -X2602Y295D01* -X1Y294D02* -X8Y294D01* -X2595Y294D02* -X2602Y294D01* -X1Y293D02* -X8Y293D01* -X2595Y293D02* -X2602Y293D01* -X1Y292D02* -X8Y292D01* -X2595Y292D02* -X2602Y292D01* -X1Y291D02* -X8Y291D01* -X2595Y291D02* -X2602Y291D01* -X1Y290D02* -X8Y290D01* -X2595Y290D02* -X2602Y290D01* -X1Y289D02* -X8Y289D01* -X2595Y289D02* -X2602Y289D01* -X1Y288D02* -X8Y288D01* -X2595Y288D02* -X2602Y288D01* -X1Y287D02* -X8Y287D01* -X2595Y287D02* -X2602Y287D01* -X1Y286D02* -X8Y286D01* -X2595Y286D02* -X2602Y286D01* -X1Y285D02* -X8Y285D01* -X2595Y285D02* -X2602Y285D01* -X1Y284D02* -X8Y284D01* -X2595Y284D02* -X2602Y284D01* -X1Y283D02* -X8Y283D01* -X2595Y283D02* -X2602Y283D01* -X1Y282D02* -X8Y282D01* -X2595Y282D02* -X2602Y282D01* -X1Y281D02* -X8Y281D01* -X2595Y281D02* -X2602Y281D01* -X1Y280D02* -X8Y280D01* -X2595Y280D02* -X2602Y280D01* -X1Y279D02* -X8Y279D01* -X2595Y279D02* -X2602Y279D01* -X1Y278D02* -X8Y278D01* -X2595Y278D02* -X2602Y278D01* -X1Y277D02* -X8Y277D01* -X2595Y277D02* -X2602Y277D01* -X1Y276D02* -X8Y276D01* -X2595Y276D02* -X2602Y276D01* -X1Y275D02* -X8Y275D01* -X2595Y275D02* -X2602Y275D01* -X1Y274D02* -X8Y274D01* -X2595Y274D02* -X2602Y274D01* -X1Y273D02* -X8Y273D01* -X2595Y273D02* -X2602Y273D01* -X1Y272D02* -X8Y272D01* -X2595Y272D02* -X2602Y272D01* -X1Y271D02* -X8Y271D01* -X2595Y271D02* -X2602Y271D01* -X1Y270D02* -X8Y270D01* -X2595Y270D02* -X2602Y270D01* -X1Y269D02* -X8Y269D01* -X2595Y269D02* -X2602Y269D01* -X1Y268D02* -X8Y268D01* -X2595Y268D02* -X2602Y268D01* -X1Y267D02* -X8Y267D01* -X2595Y267D02* -X2602Y267D01* -X1Y266D02* -X8Y266D01* -X2595Y266D02* -X2602Y266D01* -X1Y265D02* -X8Y265D01* -X2595Y265D02* -X2602Y265D01* -X1Y264D02* -X8Y264D01* -X2595Y264D02* -X2602Y264D01* -X1Y263D02* -X8Y263D01* -X2595Y263D02* -X2602Y263D01* -X1Y262D02* -X8Y262D01* -X2595Y262D02* -X2602Y262D01* -X1Y261D02* -X8Y261D01* -X2595Y261D02* -X2602Y261D01* -X1Y260D02* -X8Y260D01* -X2595Y260D02* -X2602Y260D01* -X1Y259D02* -X8Y259D01* -X2595Y259D02* -X2602Y259D01* -X1Y258D02* -X8Y258D01* -X2595Y258D02* -X2602Y258D01* -X1Y257D02* -X8Y257D01* -X2595Y257D02* -X2602Y257D01* -X1Y256D02* -X8Y256D01* -X2595Y256D02* -X2602Y256D01* -X1Y255D02* -X8Y255D01* -X2595Y255D02* -X2602Y255D01* -X1Y254D02* -X8Y254D01* -X2595Y254D02* -X2602Y254D01* -X1Y253D02* -X8Y253D01* -X2595Y253D02* -X2602Y253D01* -X1Y252D02* -X8Y252D01* -X2595Y252D02* -X2602Y252D01* -X1Y251D02* -X8Y251D01* -X2595Y251D02* -X2602Y251D01* -X1Y250D02* -X8Y250D01* -X2595Y250D02* -X2602Y250D01* -X1Y249D02* -X8Y249D01* -X2595Y249D02* -X2602Y249D01* -X1Y248D02* -X8Y248D01* -X2595Y248D02* -X2602Y248D01* -X1Y247D02* -X8Y247D01* -X2595Y247D02* -X2602Y247D01* -X1Y246D02* -X8Y246D01* -X2595Y246D02* -X2602Y246D01* -X1Y245D02* -X8Y245D01* -X2595Y245D02* -X2602Y245D01* -X1Y244D02* -X8Y244D01* -X2595Y244D02* -X2602Y244D01* -X1Y243D02* -X8Y243D01* -X2595Y243D02* -X2602Y243D01* -X1Y242D02* -X8Y242D01* -X2595Y242D02* -X2602Y242D01* -X1Y241D02* -X8Y241D01* -X2595Y241D02* -X2602Y241D01* -X1Y240D02* -X8Y240D01* -X2595Y240D02* -X2602Y240D01* -X1Y239D02* -X8Y239D01* -X2595Y239D02* -X2602Y239D01* -X1Y238D02* -X8Y238D01* -X2595Y238D02* -X2602Y238D01* -X1Y237D02* -X8Y237D01* -X2595Y237D02* -X2602Y237D01* -X1Y236D02* -X8Y236D01* -X2595Y236D02* -X2602Y236D01* -X1Y235D02* -X8Y235D01* -X2595Y235D02* -X2602Y235D01* -X1Y234D02* -X8Y234D01* -X2595Y234D02* -X2602Y234D01* -X1Y233D02* -X8Y233D01* -X2595Y233D02* -X2602Y233D01* -X1Y232D02* -X8Y232D01* -X2595Y232D02* -X2602Y232D01* -X1Y231D02* -X8Y231D01* -X2595Y231D02* -X2602Y231D01* -X1Y230D02* -X8Y230D01* -X2595Y230D02* -X2602Y230D01* -X1Y229D02* -X8Y229D01* -X2595Y229D02* -X2602Y229D01* -X1Y228D02* -X8Y228D01* -X2595Y228D02* -X2602Y228D01* -X1Y227D02* -X8Y227D01* -X2595Y227D02* -X2602Y227D01* -X1Y226D02* -X8Y226D01* -X2595Y226D02* -X2602Y226D01* -X1Y225D02* -X8Y225D01* -X2595Y225D02* -X2602Y225D01* -X1Y224D02* -X8Y224D01* -X2595Y224D02* -X2602Y224D01* -X1Y223D02* -X8Y223D01* -X2595Y223D02* -X2602Y223D01* -X1Y222D02* -X8Y222D01* -X2595Y222D02* -X2602Y222D01* -X1Y221D02* -X8Y221D01* -X2595Y221D02* -X2602Y221D01* -X1Y220D02* -X8Y220D01* -X2595Y220D02* -X2602Y220D01* -X1Y219D02* -X8Y219D01* -X2595Y219D02* -X2602Y219D01* -X1Y218D02* -X8Y218D01* -X2595Y218D02* -X2602Y218D01* -X1Y217D02* -X8Y217D01* -X2595Y217D02* -X2602Y217D01* -X1Y216D02* -X8Y216D01* -X2595Y216D02* -X2602Y216D01* -X1Y215D02* -X8Y215D01* -X2595Y215D02* -X2602Y215D01* -X1Y214D02* -X8Y214D01* -X2595Y214D02* -X2602Y214D01* -X1Y213D02* -X8Y213D01* -X2595Y213D02* -X2602Y213D01* -X1Y212D02* -X8Y212D01* -X2595Y212D02* -X2602Y212D01* -X1Y211D02* -X8Y211D01* -X2595Y211D02* -X2602Y211D01* -X1Y210D02* -X8Y210D01* -X2595Y210D02* -X2602Y210D01* -X1Y209D02* -X8Y209D01* -X2595Y209D02* -X2602Y209D01* -X1Y208D02* -X8Y208D01* -X2595Y208D02* -X2602Y208D01* -X1Y207D02* -X8Y207D01* -X2595Y207D02* -X2602Y207D01* -X1Y206D02* -X8Y206D01* -X2595Y206D02* -X2602Y206D01* -X1Y205D02* -X8Y205D01* -X2595Y205D02* -X2602Y205D01* -X1Y204D02* -X8Y204D01* -X2595Y204D02* -X2602Y204D01* -X1Y203D02* -X8Y203D01* -X2595Y203D02* -X2602Y203D01* -X1Y202D02* -X8Y202D01* -X2595Y202D02* -X2602Y202D01* -X1Y201D02* -X8Y201D01* -X2595Y201D02* -X2602Y201D01* -X1Y200D02* -X8Y200D01* -X2595Y200D02* -X2602Y200D01* -X1Y199D02* -X8Y199D01* -X2595Y199D02* -X2602Y199D01* -X1Y198D02* -X8Y198D01* -X2595Y198D02* -X2602Y198D01* -X1Y197D02* -X8Y197D01* -X2595Y197D02* -X2602Y197D01* -X1Y196D02* -X8Y196D01* -X2595Y196D02* -X2602Y196D01* -X1Y195D02* -X8Y195D01* -X2595Y195D02* -X2602Y195D01* -X1Y194D02* -X8Y194D01* -X2595Y194D02* -X2602Y194D01* -X1Y193D02* -X8Y193D01* -X2595Y193D02* -X2602Y193D01* -X1Y192D02* -X8Y192D01* -X2595Y192D02* -X2602Y192D01* -X1Y191D02* -X8Y191D01* -X2595Y191D02* -X2602Y191D01* -X1Y190D02* -X8Y190D01* -X2595Y190D02* -X2602Y190D01* -X1Y189D02* -X8Y189D01* -X2595Y189D02* -X2602Y189D01* -X1Y188D02* -X8Y188D01* -X2595Y188D02* -X2602Y188D01* -X1Y187D02* -X8Y187D01* -X2595Y187D02* -X2602Y187D01* -X1Y186D02* -X8Y186D01* -X2595Y186D02* -X2602Y186D01* -X1Y185D02* -X8Y185D01* -X2595Y185D02* -X2602Y185D01* -X1Y184D02* -X8Y184D01* -X2595Y184D02* -X2602Y184D01* -X1Y183D02* -X8Y183D01* -X2595Y183D02* -X2602Y183D01* -X1Y182D02* -X8Y182D01* -X2595Y182D02* -X2602Y182D01* -X1Y181D02* -X8Y181D01* -X2595Y181D02* -X2602Y181D01* -X1Y180D02* -X8Y180D01* -X2595Y180D02* -X2602Y180D01* -X1Y179D02* -X8Y179D01* -X2595Y179D02* -X2602Y179D01* -X1Y178D02* -X8Y178D01* -X2595Y178D02* -X2602Y178D01* -X1Y177D02* -X8Y177D01* -X2595Y177D02* -X2602Y177D01* -X1Y176D02* -X8Y176D01* -X2595Y176D02* -X2602Y176D01* -X1Y175D02* -X8Y175D01* -X2595Y175D02* -X2602Y175D01* -X1Y174D02* -X8Y174D01* -X2595Y174D02* -X2602Y174D01* -X1Y173D02* -X8Y173D01* -X2595Y173D02* -X2602Y173D01* -X1Y172D02* -X8Y172D01* -X2595Y172D02* -X2602Y172D01* -X1Y171D02* -X8Y171D01* -X2595Y171D02* -X2602Y171D01* -X1Y170D02* -X8Y170D01* -X2595Y170D02* -X2602Y170D01* -X1Y169D02* -X8Y169D01* -X2595Y169D02* -X2602Y169D01* -X1Y168D02* -X8Y168D01* -X2595Y168D02* -X2602Y168D01* -X1Y167D02* -X8Y167D01* -X2595Y167D02* -X2602Y167D01* -X1Y166D02* -X8Y166D01* -X2595Y166D02* -X2602Y166D01* -X1Y165D02* -X8Y165D01* -X2595Y165D02* -X2602Y165D01* -X1Y164D02* -X8Y164D01* -X2595Y164D02* -X2602Y164D01* -X1Y163D02* -X8Y163D01* -X2595Y163D02* -X2602Y163D01* -X1Y162D02* -X8Y162D01* -X2595Y162D02* -X2602Y162D01* -X1Y161D02* -X8Y161D01* -X2595Y161D02* -X2602Y161D01* -X1Y160D02* -X8Y160D01* -X2595Y160D02* -X2602Y160D01* -X1Y159D02* -X8Y159D01* -X2595Y159D02* -X2602Y159D01* -X1Y158D02* -X8Y158D01* -X2595Y158D02* -X2602Y158D01* -X1Y157D02* -X8Y157D01* -X2595Y157D02* -X2602Y157D01* -X1Y156D02* -X8Y156D01* -X2595Y156D02* -X2602Y156D01* -X1Y155D02* -X8Y155D01* -X2595Y155D02* -X2602Y155D01* -X1Y154D02* -X8Y154D01* -X2595Y154D02* -X2602Y154D01* -X1Y153D02* -X8Y153D01* -X2595Y153D02* -X2602Y153D01* -X1Y152D02* -X8Y152D01* -X2595Y152D02* -X2602Y152D01* -X1Y151D02* -X8Y151D01* -X2595Y151D02* -X2602Y151D01* -X1Y150D02* -X8Y150D01* -X2595Y150D02* -X2602Y150D01* -X1Y149D02* -X8Y149D01* -X2595Y149D02* -X2602Y149D01* -X1Y148D02* -X8Y148D01* -X2595Y148D02* -X2602Y148D01* -X1Y147D02* -X8Y147D01* -X2595Y147D02* -X2602Y147D01* -X1Y146D02* -X8Y146D01* -X2595Y146D02* -X2602Y146D01* -X1Y145D02* -X8Y145D01* -X2595Y145D02* -X2602Y145D01* -X1Y144D02* -X8Y144D01* -X2595Y144D02* -X2602Y144D01* -X1Y143D02* -X8Y143D01* -X2595Y143D02* -X2602Y143D01* -X1Y142D02* -X8Y142D01* -X2595Y142D02* -X2602Y142D01* -X1Y141D02* -X8Y141D01* -X2595Y141D02* -X2602Y141D01* -X1Y140D02* -X8Y140D01* -X2595Y140D02* -X2602Y140D01* -X1Y139D02* -X8Y139D01* -X2595Y139D02* -X2602Y139D01* -X1Y138D02* -X8Y138D01* -X2595Y138D02* -X2602Y138D01* -X1Y137D02* -X8Y137D01* -X2595Y137D02* -X2602Y137D01* -X1Y136D02* -X8Y136D01* -X2595Y136D02* -X2602Y136D01* -X1Y135D02* -X8Y135D01* -X2595Y135D02* -X2602Y135D01* -X1Y134D02* -X8Y134D01* -X2595Y134D02* -X2602Y134D01* -X1Y133D02* -X8Y133D01* -X2595Y133D02* -X2602Y133D01* -X1Y132D02* -X8Y132D01* -X2595Y132D02* -X2602Y132D01* -X1Y131D02* -X8Y131D01* -X2595Y131D02* -X2602Y131D01* -X1Y130D02* -X8Y130D01* -X2595Y130D02* -X2602Y130D01* -X1Y129D02* -X8Y129D01* -X2595Y129D02* -X2602Y129D01* -X1Y128D02* -X8Y128D01* -X2595Y128D02* -X2602Y128D01* -X1Y127D02* -X8Y127D01* -X2595Y127D02* -X2602Y127D01* -X1Y126D02* -X8Y126D01* -X2595Y126D02* -X2602Y126D01* -X1Y125D02* -X8Y125D01* -X2595Y125D02* -X2602Y125D01* -X1Y124D02* -X8Y124D01* -X2595Y124D02* -X2602Y124D01* -X1Y123D02* -X8Y123D01* -X2595Y123D02* -X2602Y123D01* -X1Y122D02* -X8Y122D01* -X2595Y122D02* -X2602Y122D01* -X1Y121D02* -X8Y121D01* -X2595Y121D02* -X2602Y121D01* -X1Y120D02* -X8Y120D01* -X2595Y120D02* -X2602Y120D01* -X1Y119D02* -X8Y119D01* -X2595Y119D02* -X2602Y119D01* -X1Y118D02* -X8Y118D01* -X2595Y118D02* -X2602Y118D01* -X1Y117D02* -X8Y117D01* -X2595Y117D02* -X2602Y117D01* -X1Y116D02* -X8Y116D01* -X2595Y116D02* -X2602Y116D01* -X1Y115D02* -X8Y115D01* -X2595Y115D02* -X2602Y115D01* -X1Y114D02* -X8Y114D01* -X2595Y114D02* -X2602Y114D01* -X1Y113D02* -X8Y113D01* -X2595Y113D02* -X2602Y113D01* -X1Y112D02* -X8Y112D01* -X2595Y112D02* -X2602Y112D01* -X1Y111D02* -X8Y111D01* -X2595Y111D02* -X2602Y111D01* -X1Y110D02* -X8Y110D01* -X2595Y110D02* -X2602Y110D01* -X1Y109D02* -X8Y109D01* -X2595Y109D02* -X2602Y109D01* -X1Y108D02* -X8Y108D01* -X2595Y108D02* -X2602Y108D01* -X1Y107D02* -X8Y107D01* -X2595Y107D02* -X2602Y107D01* -X1Y106D02* -X8Y106D01* -X2595Y106D02* -X2602Y106D01* -X1Y105D02* -X8Y105D01* -X2595Y105D02* -X2602Y105D01* -X1Y104D02* -X8Y104D01* -X2595Y104D02* -X2602Y104D01* -X1Y103D02* -X8Y103D01* -X2595Y103D02* -X2602Y103D01* -X1Y102D02* -X8Y102D01* -X2595Y102D02* -X2602Y102D01* -X1Y101D02* -X8Y101D01* -X2595Y101D02* -X2602Y101D01* -X1Y100D02* -X8Y100D01* -X2595Y100D02* -X2602Y100D01* -X1Y99D02* -X8Y99D01* -X2595Y99D02* -X2602Y99D01* -X1Y98D02* -X8Y98D01* -X2595Y98D02* -X2602Y98D01* -X1Y97D02* -X8Y97D01* -X2595Y97D02* -X2602Y97D01* -X1Y96D02* -X8Y96D01* -X2595Y96D02* -X2602Y96D01* -X1Y95D02* -X8Y95D01* -X2595Y95D02* -X2602Y95D01* -X1Y94D02* -X8Y94D01* -X2595Y94D02* -X2602Y94D01* -X1Y93D02* -X8Y93D01* -X2595Y93D02* -X2602Y93D01* -X1Y92D02* -X8Y92D01* -X2595Y92D02* -X2602Y92D01* -X1Y91D02* -X8Y91D01* -X2595Y91D02* -X2602Y91D01* -X1Y90D02* -X8Y90D01* -X2595Y90D02* -X2602Y90D01* -X1Y89D02* -X8Y89D01* -X2595Y89D02* -X2602Y89D01* -X1Y88D02* -X8Y88D01* -X2595Y88D02* -X2602Y88D01* -X1Y87D02* -X8Y87D01* -X2595Y87D02* -X2602Y87D01* -X1Y86D02* -X8Y86D01* -X2595Y86D02* -X2602Y86D01* -X1Y85D02* -X8Y85D01* -X1151Y85D02* -X1152Y85D01* -X2595Y85D02* -X2602Y85D01* -X1Y84D02* -X8Y84D01* -X1150Y84D02* -X1153Y84D01* -X2595Y84D02* -X2602Y84D01* -X1Y83D02* -X8Y83D01* -X1149Y83D02* -X1154Y83D01* -X2595Y83D02* -X2602Y83D01* -X1Y82D02* -X8Y82D01* -X1149Y82D02* -X1155Y82D01* -X2595Y82D02* -X2602Y82D01* -X1Y81D02* -X8Y81D01* -X1150Y81D02* -X1156Y81D01* -X2595Y81D02* -X2602Y81D01* -X1Y80D02* -X8Y80D01* -X1151Y80D02* -X1157Y80D01* -X2595Y80D02* -X2602Y80D01* -X1Y79D02* -X8Y79D01* -X1152Y79D02* -X1158Y79D01* -X2595Y79D02* -X2602Y79D01* -X1Y78D02* -X8Y78D01* -X1153Y78D02* -X1159Y78D01* -X2595Y78D02* -X2602Y78D01* -X1Y77D02* -X8Y77D01* -X1154Y77D02* -X1160Y77D01* -X2595Y77D02* -X2602Y77D01* -X1Y76D02* -X8Y76D01* -X1155Y76D02* -X1161Y76D01* -X2595Y76D02* -X2602Y76D01* -X1Y75D02* -X8Y75D01* -X1156Y75D02* -X1162Y75D01* -X2595Y75D02* -X2602Y75D01* -X1Y74D02* -X8Y74D01* -X1157Y74D02* -X1163Y74D01* -X2595Y74D02* -X2602Y74D01* -X1Y73D02* -X8Y73D01* -X1158Y73D02* -X1164Y73D01* -X2595Y73D02* -X2602Y73D01* -X1Y72D02* -X8Y72D01* -X1159Y72D02* -X1165Y72D01* -X2595Y72D02* -X2602Y72D01* -X1Y71D02* -X8Y71D01* -X1160Y71D02* -X1166Y71D01* -X2595Y71D02* -X2602Y71D01* -X1Y70D02* -X8Y70D01* -X1161Y70D02* -X1167Y70D01* -X2595Y70D02* -X2602Y70D01* -X1Y69D02* -X8Y69D01* -X1162Y69D02* -X1167Y69D01* -X2595Y69D02* -X2602Y69D01* -X1Y68D02* -X8Y68D01* -X1163Y68D02* -X1168Y68D01* -X2595Y68D02* -X2602Y68D01* -X1Y67D02* -X8Y67D01* -X1164Y67D02* -X1170Y67D01* -X2595Y67D02* -X2602Y67D01* -X1Y66D02* -X8Y66D01* -X1165Y66D02* -X1171Y66D01* -X2595Y66D02* -X2602Y66D01* -X1Y65D02* -X8Y65D01* -X1166Y65D02* -X1172Y65D01* -X2595Y65D02* -X2602Y65D01* -X1Y64D02* -X8Y64D01* -X1167Y64D02* -X1173Y64D01* -X2595Y64D02* -X2602Y64D01* -X1Y63D02* -X8Y63D01* -X1168Y63D02* -X1174Y63D01* -X2595Y63D02* -X2602Y63D01* -X1Y62D02* -X8Y62D01* -X1169Y62D02* -X1175Y62D01* -X2595Y62D02* -X2602Y62D01* -X1Y61D02* -X8Y61D01* -X1170Y61D02* -X1176Y61D01* -X2595Y61D02* -X2602Y61D01* -X1Y60D02* -X8Y60D01* -X1171Y60D02* -X1177Y60D01* -X2595Y60D02* -X2602Y60D01* -X1Y59D02* -X8Y59D01* -X1172Y59D02* -X1178Y59D01* -X2595Y59D02* -X2602Y59D01* -X1Y58D02* -X8Y58D01* -X1173Y58D02* -X1179Y58D01* -X2595Y58D02* -X2602Y58D01* -X1Y57D02* -X8Y57D01* -X1174Y57D02* -X1180Y57D01* -X2595Y57D02* -X2602Y57D01* -X1Y56D02* -X8Y56D01* -X1175Y56D02* -X1181Y56D01* -X2595Y56D02* -X2602Y56D01* -X1Y55D02* -X8Y55D01* -X1176Y55D02* -X1182Y55D01* -X2595Y55D02* -X2602Y55D01* -X1Y54D02* -X8Y54D01* -X1177Y54D02* -X1183Y54D01* -X2595Y54D02* -X2602Y54D01* -X1Y53D02* -X8Y53D01* -X1178Y53D02* -X1184Y53D01* -X2595Y53D02* -X2602Y53D01* -X1Y52D02* -X8Y52D01* -X1179Y52D02* -X1185Y52D01* -X2595Y52D02* -X2602Y52D01* -X1Y51D02* -X8Y51D01* -X1180Y51D02* -X1185Y51D01* -X2595Y51D02* -X2602Y51D01* -X1Y50D02* -X8Y50D01* -X1181Y50D02* -X1185Y50D01* -X2595Y50D02* -X2602Y50D01* -X1Y49D02* -X8Y49D01* -X1182Y49D02* -X1184Y49D01* -X2595Y49D02* -X2602Y49D01* -X1Y48D02* -X8Y48D01* -X2595Y48D02* -X2602Y48D01* -X1Y47D02* -X8Y47D01* -X2595Y47D02* -X2602Y47D01* -X1Y46D02* -X8Y46D01* -X2595Y46D02* -X2602Y46D01* -X1Y45D02* -X8Y45D01* -X2595Y45D02* -X2602Y45D01* -X1Y44D02* -X8Y44D01* -X2595Y44D02* -X2602Y44D01* -X1Y43D02* -X8Y43D01* -X2595Y43D02* -X2602Y43D01* -X1Y42D02* -X8Y42D01* -X2595Y42D02* -X2602Y42D01* -X1Y41D02* -X8Y41D01* -X2595Y41D02* -X2602Y41D01* -X1Y40D02* -X8Y40D01* -X2595Y40D02* -X2602Y40D01* -X1Y39D02* -X8Y39D01* -X2595Y39D02* -X2602Y39D01* -X1Y38D02* -X8Y38D01* -X2595Y38D02* -X2602Y38D01* -X1Y37D02* -X8Y37D01* -X2595Y37D02* -X2602Y37D01* -X1Y36D02* -X8Y36D01* -X2595Y36D02* -X2602Y36D01* -X1Y35D02* -X8Y35D01* -X2595Y35D02* -X2602Y35D01* -X1Y34D02* -X8Y34D01* -X2595Y34D02* -X2602Y34D01* -X1Y33D02* -X8Y33D01* -X2595Y33D02* -X2602Y33D01* -X1Y32D02* -X8Y32D01* -X2595Y32D02* -X2602Y32D01* -X1Y31D02* -X8Y31D01* -X2595Y31D02* -X2602Y31D01* -X1Y30D02* -X8Y30D01* -X2595Y30D02* -X2602Y30D01* -X1Y29D02* -X8Y29D01* -X2595Y29D02* -X2602Y29D01* -X1Y28D02* -X8Y28D01* -X2595Y28D02* -X2602Y28D01* -X1Y27D02* -X8Y27D01* -X2595Y27D02* -X2602Y27D01* -X1Y26D02* -X8Y26D01* -X2595Y26D02* -X2602Y26D01* -X1Y25D02* -X8Y25D01* -X2595Y25D02* -X2602Y25D01* -X1Y24D02* -X8Y24D01* -X2595Y24D02* -X2602Y24D01* -X1Y23D02* -X8Y23D01* -X2595Y23D02* -X2602Y23D01* -X1Y22D02* -X8Y22D01* -X2595Y22D02* -X2602Y22D01* -X1Y21D02* -X8Y21D01* -X2595Y21D02* -X2602Y21D01* -X1Y20D02* -X8Y20D01* -X2595Y20D02* -X2602Y20D01* -X1Y19D02* -X8Y19D01* -X2595Y19D02* -X2602Y19D01* -X1Y18D02* -X8Y18D01* -X2595Y18D02* -X2602Y18D01* -X1Y17D02* -X8Y17D01* -X2595Y17D02* -X2602Y17D01* -X1Y16D02* -X8Y16D01* -X2595Y16D02* -X2602Y16D01* -X1Y15D02* -X8Y15D01* -X2595Y15D02* -X2602Y15D01* -X1Y14D02* -X8Y14D01* -X2595Y14D02* -X2602Y14D01* -X1Y13D02* -X8Y13D01* -X2595Y13D02* -X2602Y13D01* -X1Y12D02* -X8Y12D01* -X2595Y12D02* -X2602Y12D01* -X1Y11D02* -X8Y11D01* -X2595Y11D02* -X2602Y11D01* -X1Y10D02* -X8Y10D01* -X2595Y10D02* -X2602Y10D01* -X1Y9D02* -X8Y9D01* -X2595Y9D02* -X2602Y9D01* -X1Y8D02* -X2602Y8D01* -X1Y7D02* -X2602Y7D01* -X1Y6D02* -X2602Y6D01* -X1Y5D02* -X2602Y5D01* -X1Y4D02* -X2602Y4D01* -X1Y3D02* -X2602Y3D01* -X1Y2D02* -X2602Y2D01* -X1Y1D02* -X2602Y1D01* -D02* -G04 End of Silk1* -M02* \ No newline at end of file diff --git a/src/zlac8015d_ros/launch/motor_driver_node.launch b/src/zlac8015d_ros/launch/motor_driver_node.launch index 9d10fa5..eed7e94 100644 --- a/src/zlac8015d_ros/launch/motor_driver_node.launch +++ b/src/zlac8015d_ros/launch/motor_driver_node.launch @@ -1,8 +1,7 @@   - - + - - - - diff --git a/src/zlac8015d_ros/package.xml b/src/zlac8015d_ros/package.xml index 2fa256b..4a70944 100644 --- a/src/zlac8015d_ros/package.xml +++ b/src/zlac8015d_ros/package.xml @@ -1,7 +1,7 @@ zlac8015d_ros - 0.0.1 + 0.1.8 The zlac8015d_ros package Alpacazip GPLv3 diff --git a/src/zlac8015d_ros/params/motor_driver_params.yaml b/src/zlac8015d_ros/params/motor_driver_params.yaml index b31cdcd..95d6e73 100644 --- a/src/zlac8015d_ros/params/motor_driver_params.yaml +++ b/src/zlac8015d_ros/params/motor_driver_params.yaml @@ -1,31 +1,26 @@ -# Tire & Encoder Parameters +# Wheel & Encoder Parameters # Default: 8 inches wheel ############################### -# Tire radius +# Wheel radius left_wheel_radius: 0.0974 # meter 0.1015 right_wheel_radius: 0.0974 # meter 0.1015 - # For odometry computation -computation_left_wheel_radius: 0.09806 # meter 0.1015 0.09735 +computation_left_wheel_radius: 0.09806 # meter 0.1015 computation_right_wheel_radius: 0.09794 # meter 0.1015 - # Encoder CPR(counts per revolution) cpr: 16385 ############################### -# Distance between tires +# Distance between Wheels wheels_base_width: 0.608 # meter 0.5668 # Motor automatically stops if no topics are received for a certain period of time -callback_timeout: 0.5 # seconds -# Smaller values will cause small changes in tire motion to have a greater impact on the odometry calculations -# 0.01 or 0.001 is highly recommended -decimil_coefficient: 0.001 +callback_timeout: 1.0 # seconds # Time to reach target position -set_accel_time_left: 1000 # ms -set_accel_time_right: 1000 # ms -set_decel_time_left: 1000 # ms -set_decel_time_right: 1000 # ms +set_accel_time_left: 600 #500 #1000 # ms 200 +set_accel_time_right: 600 #500 #1000 # ms 200 +set_decel_time_left: 400 #300 #1000 # ms 200 +set_decel_time_right: 400 #300 #1000 # ms 200 # Maximum rpm max_left_rpm: 150 diff --git a/src/zlac8015d_ros/scripts/ZLAC8015D.py b/src/zlac8015d_ros/scripts/ZLAC8015D.py deleted file mode 100755 index c4ffd1f..0000000 --- a/src/zlac8015d_ros/scripts/ZLAC8015D.py +++ /dev/null @@ -1,369 +0,0 @@ -#!/usr/bin/env python3 -""" -Copyright (C) 2022 rasheeddo -Copyright (C) 2022 Alpaca-zip - -This program is free software: you can redistribute it and/or modify -it under the terms of the GNU General Public License as published by -the Free Software Foundation, either version 3 of the License, or -(at your option) any later version. - -This program is distributed in the hope that it will be useful, -but WITHOUT ANY WARRANTY; without even the implied warranty of -MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -GNU General Public License for more details. - -You should have received a copy of the GNU General Public License -along with this program. If not, see . -""" - -from pymodbus.client.sync import ModbusSerialClient as ModbusClient -import numpy as np -import time - -class Controller: - - def __init__(self, port="/dev/ttyUSB0"): - - self._port = port - - self.client = ModbusClient(method='rtu', port=self._port, baudrate=115200, timeout=1) - - self.client.connect() - - self.ID = 1 - - ###################### - ## Register Address ## - ###################### - ## Common - self.CONTROL_REG = 0x200E - self.OPR_MODE = 0x200D - self.L_ACL_TIME = 0x2080 - self.R_ACL_TIME = 0x2081 - self.L_DCL_TIME = 0x2082 - self.R_DCL_TIME = 0x2083 - - ## Velocity control - self.L_CMD_RPM = 0x2088 - self.R_CMD_RPM = 0x2089 - self.L_FB_RPM = 0x20AB - self.R_FB_RPM = 0x20AC - - ## Position control - self.POS_CONTROL_TYPE = 0x200F - - self.L_MAX_RPM_POS = 0x208E - self.R_MAX_RPM_POS = 0x208F - - self.L_CMD_REL_POS_HI = 0x208A - self.L_CMD_REL_POS_LO = 0x208B - self.R_CMD_REL_POS_HI = 0x208C - self.R_CMD_REL_POS_LO = 0x208D - - self.L_FB_POS_HI = 0x20A7 - self.L_FB_POS_LO = 0x20A8 - self.R_FB_POS_HI = 0x20A9 - self.R_FB_POS_LO = 0x20AA - - ## Troubleshooting - self.L_FAULT = 0x20A5 - self.R_FAULT = 0x20A6 - - ######################## - ## Control CMDs (REG) ## - ######################## - self.EMER_STOP = 0x05 - self.ALRM_CLR = 0x06 - self.DOWN_TIME = 0x07 - self.ENABLE = 0x08 - self.POS_SYNC = 0x10 - self.POS_L_START = 0x11 - self.POS_R_START = 0x12 - - #################### - ## Operation Mode ## - #################### - self.POS_REL_CONTROL = 1 - self.POS_ABS_CONTROL = 2 - self.VEL_CONTROL = 3 - - self.ASYNC = 0 - self.SYNC = 1 - - ################# - ## Fault codes ## - ################# - self.NO_FAULT = 0x0000 - self.OVER_VOLT = 0x0001 - self.UNDER_VOLT = 0x0002 - self.OVER_CURR = 0x0004 - self.OVER_LOAD = 0x0008 - self.CURR_OUT_TOL = 0x0010 - self.ENCOD_OUT_TOL = 0x0020 - self.MOTOR_BAD = 0x0040 - self.REF_VOLT_ERROR = 0x0080 - self.EEPROM_ERROR = 0x0100 - self.WALL_ERROR = 0x0200 - self.HIGH_TEMP = 0x0400 - self.FAULT_LIST = [self.OVER_VOLT, self.UNDER_VOLT, self.OVER_CURR, self.OVER_LOAD, self.CURR_OUT_TOL, self.ENCOD_OUT_TOL, \ - self.MOTOR_BAD, self.REF_VOLT_ERROR, self.EEPROM_ERROR, self.WALL_ERROR, self.HIGH_TEMP] - - ############## - ## Odometry ## - ############## - ## 8 inches wheel - #self.travel_in_one_rev = 0.655 - self.cpr = 16385 - #self.R_Wheel = 0.105 #meter - self.left_wheel_radius = 0.105 #meter - self.right_wheel_radius = 0.105 #meter - self.left_circumference = 0.655 - self.right_circumference = 0.655 - self.computation_left_wheel_radius = 0.105 - self.computation_right_wheel_radius = 0.105 - - ## Some time if read immediatly after write, it would show ModbusIOException when get data from registers - def modbus_fail_read_handler(self, ADDR, WORD): - - read_success = False - reg = [None]*WORD - while not read_success: - result = self.client.read_holding_registers(ADDR, WORD, unit=self.ID) - try: - for i in range(WORD): - reg[i] = result.registers[i] - read_success = True - except AttributeError as e: - print(e) - time.sleep(2) - #time.sleep(0.5) - pass - - return reg - - def rpm_to_radPerSec(self, rpm): - return rpm*2*np.pi/60.0 - - """ - def rpm_to_linear(self, rpm): - - W_Wheel = self.rpm_to_radPerSec(rpm) - V = W_Wheel*self.R_Wheel - - return V - """ - - def set_mode(self, MODE): - """ - if MODE == 1: - print("Set relative position control") - elif MODE == 2: - print("Set absolute position control") - elif MODE == 3: - print("Set speed rpm control") - else: - print("set_mode ERROR: set only 1, 2, or 3") - return 0 - """ - - result = self.client.write_register(self.OPR_MODE, MODE, unit=self.ID) - return result - - def get_mode(self): - - # result = self.client.read_holding_registers(self.OPR_MODE, 1, unit=self.ID) - registers = self.modbus_fail_read_handler(self.OPR_MODE, 1) - - mode = registers[0] - - return mode - - def enable_motor(self): - result = self.client.write_register(self.CONTROL_REG, self.ENABLE, unit=self.ID) - - def disable_motor(self): - result = self.client.write_register(self.CONTROL_REG, self.DOWN_TIME, unit=self.ID) - - def estop(self): - result = self.client.write_register(self.CONTROL_REG, self.EMER_STOP, unit=self.ID) - - def get_fault_code(self): - - fault_codes = self.client.read_holding_registers(self.L_FAULT, 2, unit=self.ID) - - L_fault_code = fault_codes.registers[0] - R_fault_code = fault_codes.registers[1] - - L_fault_flag = L_fault_code in self.FAULT_LIST - R_fault_flag = R_fault_code in self.FAULT_LIST - - return (L_fault_flag, L_fault_code), (R_fault_flag, R_fault_code) - - def clear_alarm(self): - result = self.client.write_register(self.CONTROL_REG, self.ALRM_CLR, unit=self.ID) - - def set_accel_time(self, L_ms, R_ms): - - if L_ms > 32767: - L_ms = 32767 - elif L_ms < 0: - L_ms = 0 - - if R_ms > 32767: - R_ms = 32767 - elif R_ms < 0: - R_ms = 0 - - result = self.client.write_registers(self.L_ACL_TIME, [int(L_ms),int(R_ms)], unit=self.ID) - - - def set_decel_time(self, L_ms, R_ms): - - if L_ms > 32767: - L_ms = 32767 - elif L_ms < 0: - L_ms = 0 - - if R_ms > 32767: - R_ms = 32767 - elif R_ms < 0: - R_ms = 0 - - result = self.client.write_registers(self.L_DCL_TIME, [int(L_ms), int(R_ms)], unit=self.ID) - - def int16Dec_to_int16Hex(self,int16): - - lo_byte = (int16 & 0x00FF) - hi_byte = (int16 & 0xFF00) >> 8 - - all_bytes = (hi_byte << 8) | lo_byte - - return all_bytes - - - def set_rpm(self, L_rpm, R_rpm): - - if L_rpm > 3000: - L_rpm = 3000 - elif L_rpm < -3000: - L_rpm = -3000 - - if R_rpm > 3000: - R_rpm = 3000 - elif R_rpm < -3000: - R_rpm = -3000 - - left_bytes = self.int16Dec_to_int16Hex(L_rpm) - right_bytes = self.int16Dec_to_int16Hex(R_rpm) - - result = self.client.write_registers(self.L_CMD_RPM, [left_bytes, right_bytes], unit=self.ID) - - def get_rpm(self): - - - # rpms = self.client.read_holding_registers(self.L_FB_RPM, 2, unit=self.ID) - # fb_L_rpm = np.int16(rpms.registers[0])/10.0 - # fb_R_rpm = np.int16(rpms.registers[1])/10.0 - - registers = self.modbus_fail_read_handler(self.L_FB_RPM, 2) - fb_L_rpm = np.int16(registers[0])/10.0 - fb_R_rpm = np.int16(registers[1])/10.0 - - return fb_L_rpm, fb_R_rpm - - def get_linear_velocities(self): - - rpmL, rpmR = self.get_rpm() - - VL = self.rpm_to_linear(rpmL) - VR = self.rpm_to_linear(-rpmR) - - return VL, VR - - def map(self, val, in_min, in_max, out_min, out_max): - - return (val - in_min) * (out_max - out_min) / (in_max - in_min) + out_min - - def set_maxRPM_pos(self, max_L_rpm, max_R_rpm): - - if max_L_rpm > 1000: - max_L_rpm = 1000 - elif max_L_rpm < 1: - max_L_rpm = 1 - - if max_R_rpm > 1000: - max_R_rpm = 1000 - elif max_R_rpm < 1: - max_R_rpm = 1 - - result = self.client.write_registers(self.L_MAX_RPM_POS, [int(max_L_rpm), int(max_R_rpm)], unit=self.ID) - - def set_position_async_control(self): - - result = self.client.write_register(self.POS_CONTROL_TYPE, self.ASYNC, unit=self.ID) - - def move_left_wheel(self): - - result = self.client.write_register(self.CONTROL_REG, self.POS_L_START, unit=self.ID) - - def move_right_wheel(self): - - result = self.client.write_register(self.CONTROL_REG, self.POS_R_START, unit=self.ID) - - def deg_to_32bitArray(self, deg): - - dec = int(self.map(deg, -1440, 1440, -65536, 65536)) - HI_WORD = (dec & 0xFFFF0000) >> 16 - LO_WORD = dec & 0x0000FFFF - - return [HI_WORD, LO_WORD] - - def set_relative_angle(self, ang_L, ang_R): - - #L_array = self.deg_to_32bitArray(ang_L) - #R_array = self.deg_to_32bitArray(ang_R) - L_array = self.deg_to_32bitArray(ang_L/4) - R_array = self.deg_to_32bitArray(ang_R/4) - all_cmds_array = L_array + R_array - - result = self.client.write_registers(self.L_CMD_REL_POS_HI, all_cmds_array, unit=self.ID) - - def get_wheels_travelled(self): - - # read_success = False - # while not read_success: - - # result = self.client.read_holding_registers(self.L_FB_POS_HI, 4, unit=self.ID) - # try: - # l_pul_hi = result.registers[0] - # l_pul_lo = result.registers[1] - # r_pul_hi = result.registers[2] - # r_pul_lo = result.registers[3] - - # l_pulse = ((l_pul_hi & 0xFFFF) << 16) | (l_pul_lo & 0xFFFF) - # r_pulse = ((r_pul_hi & 0xFFFF) << 16) | (r_pul_lo & 0xFFFF) - # l_travelled = (float(l_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter - # r_travelled = (float(r_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter - - # read_success = True - - # except AttributeError: - # # print("error") - # pass - - registers = self.modbus_fail_read_handler(self.L_FB_POS_HI, 4) - l_pul_hi = registers[0] - l_pul_lo = registers[1] - r_pul_hi = registers[2] - r_pul_lo = registers[3] - - l_pulse = np.int32(((l_pul_hi & 0xFFFF) << 16) | (l_pul_lo & 0xFFFF)) - r_pulse = np.int32(((r_pul_hi & 0xFFFF) << 16) | (r_pul_lo & 0xFFFF)) - #l_travelled = (float(l_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter - #r_travelled = (float(r_pulse)/self.cpr)*self.travel_in_one_rev # unit in meter - - l_travelled = (float(l_pulse)/self.cpr)*self.computation_left_wheel_radius*np.pi*8 # unit in meter - r_travelled = (float(r_pulse)/self.cpr)*self.computation_right_wheel_radius*np.pi*8 # unit in meter - - return l_travelled, r_travelled diff --git a/src/zlac8015d_ros/scripts/__pycache__/ZLAC8015D.cpython-38.pyc b/src/zlac8015d_ros/scripts/__pycache__/ZLAC8015D.cpython-38.pyc deleted file mode 100644 index 7357f31..0000000 --- a/src/zlac8015d_ros/scripts/__pycache__/ZLAC8015D.cpython-38.pyc +++ /dev/null Binary files differ diff --git a/src/zlac8015d_ros/scripts/motor_driver_node.py b/src/zlac8015d_ros/scripts/motor_driver_node.py index a857603..f0002e4 100755 --- a/src/zlac8015d_ros/scripts/motor_driver_node.py +++ b/src/zlac8015d_ros/scripts/motor_driver_node.py @@ -18,61 +18,72 @@ """ import rospy -import ZLAC8015D -import tf import tf2_ros import numpy as np import time -from decimal import Decimal, ROUND_HALF_UP -from std_msgs.msg import Float32MultiArray -from std_msgs.msg import Bool -from geometry_msgs.msg import Twist +from std_msgs.msg import Float32MultiArray, Bool +from geometry_msgs.msg import Twist, TransformStamped from nav_msgs.msg import Odometry from tf.transformations import quaternion_from_euler -from geometry_msgs.msg import TransformStamped +from pymodbus.client.sync import ModbusSerialClient as ModbusClient class MotorDriverNode: def __init__(self): - print("\033[32m" + "Start motor driver node!!" + "\033[0m") - print("#########################") - #-----Initialize publisher----- + self.client = ModbusClient(method = 'rtu', port = rospy.get_param("/motor_driver_node/port"), baudrate = 115200, timeout = 1) + self.client.connect() + self.ID = 1 + + # -----Register Address----- + # Common + self.CONTROL_REG = 0x200E + self.OPR_MODE = 0x200D + self.L_ACL_TIME = 0x2080 + self.L_DCL_TIME = 0x2082 + + # Speed RPM Control + self.L_CMD_RPM = 0x2088 + + # Position Control + self.POS_CONTROL_TYPE = 0x200F + self.L_MAX_RPM_POS = 0x208E + self.L_CMD_REL_POS_HI = 0x208A + self.L_FB_POS_HI = 0x20A7 + + # -----Control CMDs (REG)----- + self.EMER_STOP = 0x05 + self.ALRM_CLR = 0x06 + self.DOWN_TIME = 0x07 + self.ENABLE = 0x08 + self.POS_L_START = 0x11 + self.POS_R_START = 0x12 + + # -----Operation Mode----- + self.ASYNC = 0 + + # -----Initialize Publisher----- self.odom_pub = rospy.Publisher("/odom", Odometry, queue_size=10) self.odom_msg = Odometry() - #-----Initialize subscriber----- - rospy.Subscriber(rospy.get_param("/motor_driver_node/twist_cmd_vel_topic"), Twist, self.zlac8015d_twist_cmd_callback) - rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_vel_topic"), Float32MultiArray, self.zlac8015d_vel_cmd_callback) - rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_rpm_topic"), Float32MultiArray, self.zlac8015d_rpm_cmd_callback) - rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_deg_topic"), Float32MultiArray, self.zlac8015d_deg_cmd_callback) - rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_dist_topic"), Float32MultiArray, self.zlac8015d_dist_cmd_callback) - #-For E-stop- - rospy.Subscriber("/estop", Bool, self.zlac8015d_estop_callback) - - #-----Initialize ZLAC8015D----- - self.zlc = ZLAC8015D.Controller(rospy.get_param("/motor_driver_node/port")) - self.zlc.cpr = int(rospy.get_param("/motor_driver_node/cpr")) - self.zlc.left_wheel_radius = float(rospy.get_param("/motor_driver_node/left_wheel_radius")) - self.zlc.right_wheel_radius = float(rospy.get_param("/motor_driver_node/right_wheel_radius")) - self.zlc.left_circumference = self.zlc.left_wheel_radius * 2 * np.pi - self.zlc.right_circumference = self.zlc.right_wheel_radius * 2 * np.pi - self.zlc.computation_left_wheel_radius = float(rospy.get_param("/motor_driver_node/computation_left_wheel_radius")) - self.zlc.computation_right_wheel_radius = float(rospy.get_param("/motor_driver_node/computation_right_wheel_radius")) - - + # -----Initialize subscriber----- + rospy.Subscriber(rospy.get_param("/motor_driver_node/twist_cmd_vel_topic"), Twist, self.twist_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_vel_topic"), Float32MultiArray, self.vel_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_rpm_topic"), Float32MultiArray, self.rpm_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_deg_topic"), Float32MultiArray, self.deg_cmd_callback) + rospy.Subscriber(rospy.get_param("/motor_driver_node/cmd_dist_topic"), Float32MultiArray, self.dist_cmd_callback) + rospy.Subscriber("/estop", Bool, self.estop_callback) + + # -----Initialize Control Mode----- self.control_mode = int(rospy.get_param("/motor_driver_node/control_mode")) - if (self.control_mode == 3): - self.zlac8015d_speed_mode_init() - elif (self.control_mode == 1): - self.zlac8015d_position_mode_init() - - #-----Initialize variable----- - self.last_subscribed_time = 0.0 - self.callback_timeout = float(rospy.get_param("/motor_driver_node/callback_timeout")) - self.deadband_rpm = int(rospy.get_param("/motor_driver_node/deadband_rpm")) + if self.control_mode == 3: + self.speed_mode_init() + elif self.control_mode == 1: + self.position_mode_init() + + # -----Initialize Variable----- self.linear_vel_cmd = 0.0 self.angular_vel_cmd = 0.0 self.got_twist_cmd = False - + self.left_vel_cmd = 0.0 self.right_vel_cmd = 0.0 self.got_vel_cmd = False @@ -81,229 +92,420 @@ self.right_rpm_cmd = 0.0 self.got_vel_rpm_cmd = False - self.left_pos_deg_cmd = 0.0 - self.right_pos_deg_cmd = 0.0 + self.left_pos_deg_cmd = 0.0 + self.right_pos_deg_cmd = 0.0 self.got_pos_deg_cmd = False self.left_pos_dist_cmd = 0.0 self.right_pos_dist_cmd = 0.0 self.got_pos_dist_cmd = False - - self.theta = 0.0 + + self.estop = False + + self.last_subscribed_time = 0.0 + self.callback_timeout = float(rospy.get_param("/motor_driver_node/callback_timeout")) + self.wheels_base_width = float(rospy.get_param("/motor_driver_node/wheels_base_width")) + self.left_wheel_radius = float(rospy.get_param("/motor_driver_node/left_wheel_radius")) + self.right_wheel_radius = float(rospy.get_param("/motor_driver_node/right_wheel_radius")) + self.computation_left_wheel_radius = float(rospy.get_param("/motor_driver_node/computation_left_wheel_radius")) + self.computation_right_wheel_radius = float(rospy.get_param("/motor_driver_node/computation_right_wheel_radius")) + self.cpr = int(rospy.get_param("/motor_driver_node/cpr")) + self.deadband_rpm = int(rospy.get_param("/motor_driver_node/deadband_rpm")) + self.left_rpm_lim = int(rospy.get_param("/motor_driver_node/max_left_rpm")) + self.right_rpm_lim = int(rospy.get_param("/motor_driver_node/max_right_rpm")) + self.publish_TF = rospy.get_param("/motor_driver_node/publish_TF") + self.publish_odom = rospy.get_param("/motor_driver_node/publish_odom") + self.TF_header_frame = rospy.get_param("/motor_driver_node/TF_header_frame") + self.TF_child_frame = rospy.get_param("/motor_driver_node/TF_child_frame") + self.odom_header_frame = rospy.get_param("/motor_driver_node/odom_header_frame") + self.odom_child_frame = rospy.get_param("/motor_driver_node/odom_child_frame") + self.debug = rospy.get_param("/motor_driver_node/debug") + self.period = 0.05 self.x = 0.0 self.y = 0.0 - self.Wr = 0.0 - self.Wl = 0.0 - self.period = 0.05 + self.theta = 0.0 self.l_meter = 0.0 self.r_meter = 0.0 - self.l_meter_init, self.r_meter_init = self.zlc.get_wheels_travelled() self.prev_l_meter = 0.0 self.prev_r_meter = 0.0 - self.wheels_base_width = float(rospy.get_param("/motor_driver_node/wheels_base_width")) - - self.br = tf2_ros.TransformBroadcaster() + self.l_meter_init, self.r_meter_init = self.get_wheels_travelled() self.t = TransformStamped() + self.br = tf2_ros.TransformBroadcaster() self.state_vector = np.zeros((3, 1)) - - #-For E-stop- - self.estop = False - - + + print("\033[32m" + "Start ZLAC8015D motor driver node" + "\033[0m") + print("#########################") + """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_estop_callback function - ++++++++++++++++++++++++++++++++++++++++++ - Callback function to subscribe for "/estop". + ############################## + ## speed_mode_init function ## + ############################## + Initialization of speed RPM control mode. """ - def zlac8015d_estop_callback(self, msg): - self.estop = msg.data - + def speed_mode_init(self): + # -----Disable Motor----- + result = self.client.write_register(self.CONTROL_REG, self.DOWN_TIME, unit = self.ID) + + # -----Set Accel Time----- + AL_ms = int(rospy.get_param("/motor_driver_node/set_accel_time_left")) + AR_ms = int(rospy.get_param("/motor_driver_node/set_accel_time_right")) + if AL_ms > 32767: + AL_ms = 32767 + elif AL_ms < 0: + AL_ms = 0 + + if AR_ms > 32767: + AR_ms = 32767 + elif AR_ms < 0: + AR_ms = 0 + + result = self.client.write_registers(self.L_ACL_TIME, [AL_ms, AR_ms], unit = self.ID) + + # -----Set Decel Time----- + DL_ms = int(rospy.get_param("/motor_driver_node/set_decel_time_left")) + DR_ms = int(rospy.get_param("/motor_driver_node/set_decel_time_right")) + if DL_ms > 32767: + DL_ms = 32767 + elif DL_ms < 0: + DL_ms = 0 + + if DR_ms > 32767: + DR_ms = 32767 + elif DR_ms < 0: + DR_ms = 0 + + result = self.client.write_registers(self.L_DCL_TIME, [DL_ms, DR_ms], unit = self.ID) + + # -----Set Mode----- + mode = 3 + result = self.client.write_register(self.OPR_MODE, mode, unit=self.ID) + print("\033[32m" + "Set mode as speed RPM control" + "\033[0m") + + # -----Enable Motor----- + result = self.client.write_register(self.CONTROL_REG, self.ENABLE, unit = self.ID) + """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_twist_cmd_callback function - ++++++++++++++++++++++++++++++++++++++++++ + ################################# + ## position_mode_init function ## + ################################# + Initialization of relative position control mode. + """ + def position_mode_init(self): + # -----Disable Motor----- + result = self.client.write_register(self.CONTROL_REG, self.DOWN_TIME, unit = self.ID) + + # -----Set Accel Time----- + AL_ms = int(rospy.get_param("/motor_driver_node/set_accel_time_left")) + AR_ms = int(rospy.get_param("/motor_driver_node/set_accel_time_right")) + if AL_ms > 32767: + AL_ms = 32767 + elif AL_ms < 0: + AL_ms = 0 + + if AR_ms > 32767: + AR_ms = 32767 + elif AR_ms < 0: + AR_ms = 0 + + result = self.client.write_registers(self.L_ACL_TIME, [AL_ms, AR_ms], unit = self.ID) + + # -----Set Decel Time----- + DL_ms = int(rospy.get_param("/motor_driver_node/set_decel_time_left")) + DR_ms = int(rospy.get_param("/motor_driver_node/set_decel_time_right")) + if DL_ms > 32767: + DL_ms = 32767 + elif DL_ms < 0: + DL_ms = 0 + + if DR_ms > 32767: + DR_ms = 32767 + elif DR_ms < 0: + DR_ms = 0 + + result = self.client.write_registers(self.L_DCL_TIME, [DL_ms, DR_ms], unit = self.ID) + + # -----Set Mode----- + mode = 1 + result = self.client.write_register(self.OPR_MODE, mode, unit=self.ID) + print("\033[32m" + "Set mode as relative position control" + "\033[0m") + + # -----Set Position Async Control----- + result = self.client.write_register(self.POS_CONTROL_TYPE, self.ASYNC, unit = self.ID) + + # -----Set Position Async Control----- + max_L_rpm = int(rospy.get_param("/motor_driver_node/max_left_rpm")) + max_R_rpm = int(rospy.get_param("/motor_driver_node/max_right_rpm")) + if max_L_rpm > 1000: + max_L_rpm = 1000 + elif max_L_rpm < 1: + max_L_rpm = 1 + + if max_R_rpm > 1000: + max_R_rpm = 1000 + elif max_R_rpm < 1: + max_R_rpm = 1 + + result = self.client.write_registers(self.L_MAX_RPM_POS, [max_L_rpm, max_R_rpm], unit = self.ID) + + # -----Enable Motor----- + result = self.client.write_register(self.CONTROL_REG, self.ENABLE, unit = self.ID) + + """ + ################################# + ## twist_cmd_callback function ## + ################################# Callback function to subscribe for "/zlac8015d/twist/cmd_vel". """ - def zlac8015d_twist_cmd_callback(self, msg): + def twist_cmd_callback(self, msg): self.linear_vel_cmd = msg.linear.x self.angular_vel_cmd = msg.angular.z self.got_twist_cmd = True self.last_subscribed_time = time.perf_counter() - + """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_vel_cmd_callback function - ++++++++++++++++++++++++++++++++++++++++++ + ############################### + ## vel_cmd_callback function ## + ############################### Callback function to subscribe for "/zlac8015d/vel/cmd_vel". """ - def zlac8015d_vel_cmd_callback(self, msg): + def vel_cmd_callback(self, msg): self.left_vel_cmd = msg.data[0] self.right_vel_cmd = -msg.data[1] self.got_vel_cmd = True self.last_subscribed_time = time.perf_counter() """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_rpm_cmd_callback function - ++++++++++++++++++++++++++++++++++++++++++ + ############################### + ## rpm_cmd_callback function ## + ############################### Callback function to subscribe for "/zlac8015d/vel/cmd_rpm". """ - def zlac8015d_rpm_cmd_callback(self, msg): + def rpm_cmd_callback(self, msg): self.left_rpm_cmd = msg.data[0] self.right_rpm_cmd = -msg.data[1] self.got_vel_rpm_cmd = True self.last_subscribed_time = time.perf_counter() """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_deg_cmd_callback function - ++++++++++++++++++++++++++++++++++++++++++ + ############################### + ## deg_cmd_callback function ## + ############################### Callback function to subscribe for "/zlac8015d/pos/cmd_deg". """ - def zlac8015d_deg_cmd_callback(self, msg): + def deg_cmd_callback(self, msg): self.left_pos_deg_cmd = msg.data[0] self.right_pos_deg_cmd = -msg.data[1] self.got_pos_deg_cmd = True """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_dist_cmd_callback function - ++++++++++++++++++++++++++++++++++++++++++ + ################################ + ## dist_cmd_callback function ## + ################################ Callback function to subscribe for "/zlac8015d/pos/cmd_dist". """ - def zlac8015d_dist_cmd_callback(self, msg): + def dist_cmd_callback(self, msg): self.left_pos_dist_cmd = msg.data[0] self.right_pos_dist_cmd = msg.data[1] self.got_pos_dist_cmd = True + + """ + ############################## + ## estop_callback function ## + ############################## + Callback function to subscribe for "/estop". + """ + def estop_callback(self, msg): + self.estop = msg.data """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_speed_mode_init function - ++++++++++++++++++++++++++++++++++++++++++ - Initialization of speed rpm control mode. - """ - def zlac8015d_speed_mode_init(self): - self.zlc.disable_motor() - self.zlc.set_accel_time(int(rospy.get_param("/motor_driver_node/set_accel_time_left")), int(rospy.get_param("/motor_driver_node/set_accel_time_right"))) - self.zlc.set_decel_time(int(rospy.get_param("/motor_driver_node/set_decel_time_left")), int(rospy.get_param("/motor_driver_node/set_accel_time_right"))) - self.zlc.set_mode(3) - self.zlc.enable_motor() - - """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_position_mode_init function - ++++++++++++++++++++++++++++++++++++++++++ - Initialization of relative position control mode. - """ - def zlac8015d_position_mode_init(self): - self.zlc.disable_motor() - self.zlc.set_accel_time(int(rospy.get_param("/motor_driver_node/set_accel_time_left")), int(rospy.get_param("/motor_driver_node/set_accel_time_right"))) - self.zlc.set_decel_time(int(rospy.get_param("/motor_driver_node/set_decel_time_left")), int(rospy.get_param("/motor_driver_node/set_decel_time_right"))) - self.zlc.set_mode(1) - self.zlc.set_position_async_control() - self.zlc.set_maxRPM_pos(int(rospy.get_param("/motor_driver_node/max_left_rpm")), int(rospy.get_param("/motor_driver_node/max_right_rpm"))) - self.zlc.enable_motor() - - """ - ++++++++++++++++++++++++++++++++++++++++++ - twist_to_rpm function - ++++++++++++++++++++++++++++++++++++++++++ - Convert from twist to rpm. + ########################### + ## twist_to_rpm function ## + ########################### + Convert from twist to RPM. """ def twist_to_rpm(self, linear_vel, angular_vel): left_vel = linear_vel - self.wheels_base_width / 2 * angular_vel right_vel = linear_vel + self.wheels_base_width / 2 * angular_vel left_rpm, right_rpm = self.vel_to_rpm(left_vel, -right_vel) return left_rpm, right_rpm - + """ - ++++++++++++++++++++++++++++++++++++++++++ - vel_to_rpm function - ++++++++++++++++++++++++++++++++++++++++++ - Convert from speed to rpm. + ######################### + ## vel_to_rpm function ## + ######################### + Convert from speed to RPM. """ def vel_to_rpm(self, left_vel, right_vel): - left_rpm = 60 * left_vel / (2 * np.pi * self.zlc.left_wheel_radius) - right_rpm = 60 * right_vel / (2 * np.pi * self.zlc.right_wheel_radius) + left_rpm = 60 * left_vel / (2 * np.pi * self.left_wheel_radius) + right_rpm = 60 * right_vel / (2 * np.pi * self.right_wheel_radius) return left_rpm, right_rpm + + """ + ##################################### + ## dist_to_relative_angle function ## + ##################################### + Convert from distance to relative angle. + """ + def dist_to_relative_angle(self, left_dist, right_dist): + left_circumference = self.left_wheel_radius * 2 * np.pi + right_circumference = self.right_wheel_radius * 2 * np.pi + left_relative_deg = (left_dist * 360.0) / left_circumference + right_relative_deg = (-right_dist * 360.0) / right_circumference + return left_relative_deg, right_relative_deg """ - ++++++++++++++++++++++++++++++++++++++++++ - zlac8015d_set_rpm_with_limit function - ++++++++++++++++++++++++++++++++++++++++++ - Set rpm with limit. + ################################### + ## int16Dec_to_int16Hex function ## + ################################### + Convert from int16Dec to int16Hex. """ - def zlac8015d_set_rpm_with_limit(self, left_rpm, right_rpm): - left_rpm_lim = int(rospy.get_param("/motor_driver_node/max_left_rpm")) - right_rpm_lim = int(rospy.get_param("/motor_driver_node/max_right_rpm")) - if ((-left_rpm_lim < left_rpm < left_rpm_lim) and (-right_rpm_lim < right_rpm < right_rpm_lim)): - if (-self.deadband_rpm < left_rpm < self.deadband_rpm): - left_rpm = 0 - if (-self.deadband_rpm < right_rpm < self.deadband_rpm): - right_rpm = 0 - - self.zlc.set_rpm(int(left_rpm), int(right_rpm)) - else: - rospy.logerr("Set RPM exceeds the limit.") + def int16Dec_to_int16Hex(self, int16): + lo_byte = (int16 & 0x00FF) + hi_byte = (int16 & 0xFF00) >> 8 + all_bytes = (hi_byte << 8) | lo_byte + return all_bytes """ - ++++++++++++++++++++++++++++++++++++++++++ - calculate_odometry function - ++++++++++++++++++++++++++++++++++++++++++ + ################################# + ## deg_to_32bitArray function ## + ################################# + Convert from degree to 32bitArray. + """ + def deg_to_32bitArray(self, deg): + dec = int((deg + 1440) * (65536 + 65536) / (1440 + 1440) - 65536) + HI_WORD = (dec & 0xFFFF0000) >> 16 + LO_WORD = dec & 0x0000FFFF + return [HI_WORD, LO_WORD] + + """ + ################################### + ## get_wheels_travelled function ## + ################################### + Get distance traveled by left and right wheels. + """ + def get_wheels_travelled(self): + registers = self.modbus_fail_read_handler(self.L_FB_POS_HI, 4) + l_pul_hi = registers[0] + l_pul_lo = registers[1] + r_pul_hi = registers[2] + r_pul_lo = registers[3] + l_pulse = np.int32(((l_pul_hi & 0xFFFF) << 16) | (l_pul_lo & 0xFFFF)) + r_pulse = np.int32(((r_pul_hi & 0xFFFF) << 16) | (r_pul_lo & 0xFFFF)) + l_travelled = (float(l_pulse) / self.cpr) * self.computation_left_wheel_radius * np.pi * 8 # unit in meter + r_travelled = (float(r_pulse) / self.cpr) * self.computation_right_wheel_radius * np.pi * 8 # unit in meter + return l_travelled, r_travelled + + """ + ####################################### + ## modbus_fail_read_handler function ## + ####################################### + Get data from registers. + """ + def modbus_fail_read_handler(self, ADDR, WORD): + read_success = False + reg = [None] * WORD + while not read_success: + result = self.client.read_holding_registers(ADDR, WORD, unit = self.ID) + try: + for i in range(WORD): + reg[i] = result.registers[i] + read_success = True + except AttributeError as e: + print(e) + pass + return reg + + """ + ################################# + ## set_rpm_with_limit function ## + ################################# + Set RPM with limit. + """ + def set_rpm_with_limit(self, left_rpm, right_rpm): + if self.left_rpm_lim < left_rpm: + left_rpm = self.left_rpm_lim + rospy.logwarn("RPM reach the limit.") + elif left_rpm < -self.left_rpm_lim: + left_rpm = -self.left_rpm_lim + rospy.logwarn("RPM reach the limit.") + elif -self.deadband_rpm < left_rpm < self.deadband_rpm: + left_rpm = 0 + + if self.right_rpm_lim < right_rpm: + right_rpm = self.right_rpm_lim + rospy.logwarn("RPM reach the limit.") + elif right_rpm < -self.right_rpm_lim: + right_rpm = -self.right_rpm_lim + rospy.logwarn("RPM reach the limit.") + elif -self.deadband_rpm < right_rpm < self.deadband_rpm: + right_rpm = 0 + + left_bytes = self.int16Dec_to_int16Hex(int(left_rpm)) + right_bytes = self.int16Dec_to_int16Hex(int(right_rpm)) + result = self.client.write_registers(self.L_CMD_RPM, [left_bytes, right_bytes], unit = self.ID) + + """ + ################################# + ## set_relative_angle function ## + ################################# + Set relative angle. + """ + def set_relative_angle(self, ang_L, ang_R): + L_array = self.deg_to_32bitArray(ang_L / 4) + R_array = self.deg_to_32bitArray(ang_R / 4) + all_cmds_array = L_array + R_array + result = self.client.write_registers(self.L_CMD_REL_POS_HI, all_cmds_array, unit = self.ID) + + """ + ################################# + ## calculate_odometry function ## + ################################# Odometry computation. """ def calculate_odometry(self): - """ - l_rpm, r_rpm = self.zlc.get_rpm() - self.Wl = self.zlc.rpm_to_radPerSec(l_rpm) - self.Wr = self.zlc.rpm_to_radPerSec(-r_rpm) - """ - self.l_meter, self.r_meter = self.zlc.get_wheels_travelled() + self.l_meter, self.r_meter = self.get_wheels_travelled() self.l_meter = self.l_meter - self.l_meter_init self.r_meter = (-1 * self.r_meter) - (-1 * self.r_meter_init) vl = (self.l_meter - self.prev_l_meter) / self.period vr = (self.r_meter - self.prev_r_meter) / self.period - self.Wl = vl / self.zlc.computation_left_wheel_radius - self.Wr = vr / self.zlc.computation_right_wheel_radius - - matrix = np.array([[self.zlc.computation_right_wheel_radius / 2, self.zlc.computation_left_wheel_radius / 2], [self.zlc.computation_right_wheel_radius / self.wheels_base_width, -self.zlc.computation_left_wheel_radius / self.wheels_base_width]]) - vector = np.array([[self.Wr], [self.Wl]]) + Wl = vl / self.computation_left_wheel_radius + Wr = vr / self.computation_right_wheel_radius + matrix = np.array([[self.computation_right_wheel_radius / 2, self.computation_left_wheel_radius / 2], [self.computation_right_wheel_radius / self.wheels_base_width, -self.computation_left_wheel_radius / self.wheels_base_width]]) + vector = np.array([[Wr], [Wl]]) input_vector = np.dot(matrix, vector) V = input_vector[0, 0] Wz = input_vector[1, 0] - out_matrix = np.array([[1, 0, 0], [0, 1, 0], [0, 0, 1]]) dirc_matrix = np.array([[np.cos(self.state_vector[2, 0]) * self.period, 0], [np.sin(self.state_vector[2, 0]) * self.period, 0], [0, self.period]]) out_vector = np.dot(out_matrix, self.state_vector) + np.dot(dirc_matrix, input_vector) - self.x = out_vector[0, 0] - self.y = out_vector[1, 0] - self.theta = out_vector[2, 0] + x = out_vector[0, 0] + y = out_vector[1, 0] + theta = out_vector[2, 0] - #-----Construct tf----- - if(rospy.get_param("/motor_driver_node/publish_TF")): + # -----Construct TF----- + if(self.publish_TF): self.t.header.stamp = rospy.Time.now() - self.t.header.frame_id = rospy.get_param("/motor_driver_node/TF_header_frame") - self.t.child_frame_id = rospy.get_param("/motor_driver_node/TF_child_frame") - self.t.transform.translation.x = self.x - self.t.transform.translation.y = self.y + self.t.header.frame_id = self.TF_header_frame + self.t.child_frame_id = self.TF_child_frame + self.t.transform.translation.x = x + self.t.transform.translation.y = y self.t.transform.translation.z = 0.0 - rotation = tf.transformations.quaternion_from_euler(0, 0, self.theta) + rotation = quaternion_from_euler(0, 0, theta) self.t.transform.rotation.x = rotation[0] self.t.transform.rotation.y = rotation[1] self.t.transform.rotation.z = rotation[2] self.t.transform.rotation.w = rotation[3] self.br.sendTransform(self.t) - #-----Construct odom message----- - if(rospy.get_param("/motor_driver_node/publish_odom")): + # -----Construct Odom Message----- + if(self.publish_odom): self.odom_msg.header.stamp = rospy.Time.now() - self.odom_msg.header.frame_id = rospy.get_param("/motor_driver_node/odom_header_frame") - self.odom_msg.child_frame_id = rospy.get_param("/motor_driver_node/odom_child_frame") - self.odom_msg.pose.pose.position.x = self.x - self.odom_msg.pose.pose.position.y = self.y + self.odom_msg.header.frame_id = self.odom_header_frame + self.odom_msg.child_frame_id = self.odom_child_frame + self.odom_msg.pose.pose.position.x = x + self.odom_msg.pose.pose.position.y = y self.odom_msg.pose.pose.position.z = 0.0 - orientation = tf.transformations.quaternion_from_euler(0, 0, self.theta) + orientation = quaternion_from_euler(0, 0, theta) self.odom_msg.pose.pose.orientation.x = orientation[0] self.odom_msg.pose.pose.orientation.y = orientation[1] self.odom_msg.pose.pose.orientation.z = orientation[2] @@ -318,168 +520,114 @@ self.odom_msg.twist.twist.linear.y = 0.0 self.odom_msg.twist.twist.angular.z = Wz self.odom_pub.publish(self.odom_msg) - - self.state_vector[0, 0] = self.x - self.state_vector[1, 0] = self.y - self.state_vector[2, 0] = self.theta - - """ - def calculate_odometry(self): - self.l_meter, self.r_meter = self.zlc.get_wheels_travelled() - self.l_meter = self.l_meter - self.l_meter_init - self.r_meter = (-1 * self.r_meter) - (-1 * self.r_meter_init) - if (self.control_mode == 3): - vl, vr = self.zlc.get_linear_velocities() - elif (self.control_mode == 1): - vl = (self.l_meter - self.prev_l_meter) / self.period - vr = (self.r_meter - self.prev_r_meter) / self.period - - round_vl = float(Decimal(str(vl)).quantize(Decimal(str(rospy.get_param("/motor_driver_node/decimil_coefficient"))), rounding = ROUND_HALF_UP)) - round_vr = float(Decimal(str(vr)).quantize(Decimal(str(rospy.get_param("/motor_driver_node/decimil_coefficient"))), rounding = ROUND_HALF_UP)) - - #-----Rotatiing----- - if ((round_vl * round_vr) < 0.0) and (abs(round_vl) == abs(round_vr)): - V = 0.0 - Wz = 2.0 * vr / self.wheels_base_width - self.theta = self.theta + Wz * self.period - path = "Rotatiing" - - #-----Curving----- - elif ((round_vl - round_vr) != 0): - V = (vl + vr) / 2.0 - Wz = (vr - vl) / self.wheels_base_width - R_ICC = (self.wheels_base_width / 2.0) * ((vr + vl) / (vr - vl)) - self.x = self.x - R_ICC * np.sin(self.theta) + R_ICC * np.sin(self.theta + Wz * self.period) - self.y = self.y + R_ICC * np.cos(self.theta) - R_ICC * np.cos(self.theta + Wz * self.period) - self.theta = self.theta + Wz * self.period - path = "Curving" - - #-----Going straight----- - else: - V = (vl + vr)/2.0 - Wz = 0.0 - self.x = self.x + V * np.cos(self.theta) * self.period - self.y = self.y + V * np.sin(self.theta) * self.period - path = "Going straight" - #-----Construct tf----- - q = quaternion_from_euler(0, 0, self.theta) - if(rospy.get_param("/motor_driver_node/publish_TF")): - self.t.header.stamp = rospy.Time.now() - self.t.header.frame_id = rospy.get_param("/motor_driver_node/TF_header_frame") - self.t.child_frame_id = rospy.get_param("/motor_driver_node/TF_child_frame") - self.t.transform.translation.x = self.x - self.t.transform.translation.y = self.y - self.t.transform.translation.z = 0.0 - self.t.transform.rotation.x = q[0] - self.t.transform.rotation.y = q[1] - self.t.transform.rotation.z = q[2] - self.t.transform.rotation.w = q[3] - self.br.sendTransform(self.t) - - #-----Construct odom message----- - if(rospy.get_param("/motor_driver_node/publish_odom")): - self.odom_msg.header.stamp = rospy.Time.now() - self.odom_msg.header.frame_id = rospy.get_param("/motor_driver_node/odom_header_frame") - self.odom_msg.child_frame_id = rospy.get_param("/motor_driver_node/odom_child_frame") - self.odom_msg.pose.pose.position.x = self.x - self.odom_msg.pose.pose.position.y = self.y - self.odom_msg.pose.pose.position.z = 0.0 - self.odom_msg.pose.pose.orientation.x = q[0] - self.odom_msg.pose.pose.orientation.y = q[1] - self.odom_msg.pose.pose.orientation.z = q[2] - self.odom_msg.pose.pose.orientation.w = q[3] - self.odom_msg.pose.covariance[0] = 0.0001 - self.odom_msg.pose.covariance[7] = 0.0001 - self.odom_msg.pose.covariance[14] = 0.000001 - self.odom_msg.pose.covariance[21] = 0.000001 - self.odom_msg.pose.covariance[28] = 0.000001 - self.odom_msg.pose.covariance[35] = 0.0001 - self.odom_msg.twist.twist.linear.x = V - self.odom_msg.twist.twist.linear.y = 0.0 - self.odom_msg.twist.twist.angular.z = Wz - self.odom_pub.publish(self.odom_msg) - - return vl, vr - """ + self.state_vector[0, 0] = x + self.state_vector[1, 0] = y + self.state_vector[2, 0] = theta + return x, y, theta """ - ++++++++++++++++++++++++++++++++++++++++++ - control_loop function - ++++++++++++++++++++++++++++++++++++++++++ + ############################## + ## control_loop function ## + ############################## Control loop. """ def control_loop(self): - rate = rospy.Rate(20) # 20Hz - reset_flag = False + rate = rospy.Rate(1 / self.period) + estop_reset_flag = False + while True: - if (rospy.is_shutdown()): - self.zlc.disable_motor() + if rospy.is_shutdown(): + # -----Disable Motor----- + result = self.client.write_register(self.CONTROL_REG, self.DOWN_TIME, unit = self.ID) break - + start_time = time.perf_counter() - - if (self.estop == True): - self.zlc.estop() - reset_flag = True - else: - if(reset_flag == True): - self.zlc.clear_alarm() - self.zlc.disable_motor() - self.zlc.enable_motor() - reset_flag = False - #-----Speed rpm control mode----- - if (self.control_mode == 3): - if (self.got_twist_cmd): + if self.estop: + # -----Emergency Stop----- + if self.control_mode == 3: + self.set_rpm_with_limit(0, 0) + elif self.control_mode == 1: + result = self.client.write_register(self.CONTROL_REG, self.EMER_STOP, unit=self.ID) + + if not estop_reset_flag: + #result = self.client.write_register(self.CONTROL_REG, self.EMER_STOP, unit=self.ID) + + rospy.logwarn("####################") + rospy.logwarn("---EMERGENCY STOP---") + rospy.logwarn("####################") + estop_reset_flag = True + elif not self.estop: + if estop_reset_flag: + # -----Clear Alarm----- + result = self.client.write_register(self.CONTROL_REG, self.ALRM_CLR, unit=self.ID) + + # -----Disable Motor----- + result = self.client.write_register(self.CONTROL_REG, self.DOWN_TIME, unit = self.ID) + + # -----Enable Motor----- + result = self.client.write_register(self.CONTROL_REG, self.ENABLE, unit = self.ID) + + estop_reset_flag = False + + # -----Speed RPM Control----- + if self.control_mode == 3: + if self.got_twist_cmd: self.left_rpm_cmd, self.right_rpm_cmd = self.twist_to_rpm(self.linear_vel_cmd, self.angular_vel_cmd) - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + self.set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) self.got_twist_cmd = False - elif (self.got_vel_cmd): + elif self.got_vel_cmd: self.left_rpm_cmd, self.right_rpm_cmd = self.vel_to_rpm(self.left_vel_cmd, self.right_vel_cmd) - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + self.set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) self.got_vel_cmd = False - elif (self.got_vel_rpm_cmd): - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + elif self.got_vel_rpm_cmd: + self.set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) self.got_vel_rpm_cmd = False - elif (time.perf_counter() - self.last_subscribed_time > self.callback_timeout): + elif (time.perf_counter() - self.last_subscribed_time) > self.callback_timeout: self.left_rpm_cmd = 0.0 self.right_rpm_cmd = 0.0 - self.zlac8015d_set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) - - #-----relative position control mode----- - elif (self.control_mode == 1): - if (self.got_pos_deg_cmd): - self.zlc.set_relative_angle(self.left_pos_deg_cmd ,self.right_pos_deg_cmd) - self.zlc.move_left_wheel() - self.zlc.move_right_wheel() + self.set_rpm_with_limit(self.left_rpm_cmd, self.right_rpm_cmd) + + # -----Position Control----- + elif self.control_mode == 1: + if self.got_pos_deg_cmd: + self.set_relative_angle(self.left_pos_deg_cmd ,self.right_pos_deg_cmd) + # -----Move Left Wheel----- + result = self.client.write_register(self.CONTROL_REG, self.POS_L_START, unit=self.ID) + + # -----Move Right Wheel----- + result = self.client.write_register(self.CONTROL_REG, self.POS_R_START, unit=self.ID) + self.got_pos_deg_cmd = False - elif (self.got_pos_dist_cmd): - left_cmd_deg = (self.left_pos_dist_cmd * 360.0) / self.zlc.left_circumference - right_cmd_deg = (-self.right_pos_dist_cmd * 360.0) / self.zlc.right_circumference - self.zlc.set_relative_angle(left_cmd_deg, right_cmd_deg) - self.zlc.move_left_wheel() - self.zlc.move_right_wheel() + elif self.got_pos_dist_cmd: + self.left_pos_deg_cmd, self.right_pos_deg_cmd = self.dist_to_relative_angle(self.left_pos_dist_cmd, self.right_pos_dist_cmd) + self.set_relative_angle(self.left_pos_deg_cmd ,self.right_pos_deg_cmd) + # -----Move Left Wheel----- + result = self.client.write_register(self.CONTROL_REG, self.POS_L_START, unit=self.ID) + + # -----Move Right Wheel----- + result = self.client.write_register(self.CONTROL_REG, self.POS_R_START, unit=self.ID) + self.got_pos_dist_cmd = False #-----Odometry computation----- - self.calculate_odometry() + x, y, theta = self.calculate_odometry() self.period = time.perf_counter() - start_time self.prev_l_meter = self.l_meter self.prev_r_meter = self.r_meter - #-----Logging to screen----- - if (rospy.get_param("/motor_driver_node/debug")): - print("\033[32m" + "x: {:f} | y: {:f} | yaw: {:f} | Wr: {:f} | Wl: {:f}".format(self.x, self.y, np.rad2deg(self.theta), self.Wr, self.Wl) + "\033[0m") + #-----Debugging Feature----- + if (self.debug): + print("\033[32m" + "x: {:f} | y: {:f} | yaw: {:f}".format(x, y, np.rad2deg(theta)) + "\033[0m") else: - #print("\033[32m" + "Debugging features disable" + "\033[0m") pass - - rate.sleep() + rate.sleep() + """ -++++++++++++++++++++++++++++++++++++++++++ - main function -++++++++++++++++++++++++++++++++++++++++++ +################### +## Main function ## +################### Main. """ def main():